@@ -39,7 +39,7 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt
39
39
// Parameter
40
40
time_stamp_field_name_ = declare_parameter (" time_stamp_field_name" , " time_stamp" );
41
41
use_imu_ = declare_parameter (" use_imu" , true );
42
- update_azimuth_and_distance_ = declare_parameter<bool >(" update_azimuth_and_distance" );
42
+ update_azimuth_and_distance_ = declare_parameter<bool >(" update_azimuth_and_distance" , true );
43
43
44
44
// Publisher
45
45
undistorted_points_pub_ =
@@ -246,6 +246,15 @@ bool DistortionCorrectorComponent::undistortPointCloud(
246
246
bool need_transform = points.header .frame_id != base_link_frame_;
247
247
248
248
for (; it_x != it_x.end (); ++it_x, ++it_y, ++it_z, ++it_azimuth, ++it_distance, ++it_time_stamp) {
249
+ if (update_azimuth_and_distance_ && !has_azimuth_transformation_) {
250
+ // calculate the relation between the Lidar azimuth coordinate and the Cartesian coordinate
251
+ // system 360 - atan(xy) - Lidar azimuth = offset azimuth transformation = 360 - offset =
252
+ // atan(xy) + Lidar azimuth
253
+ azimuth_transformation_ = cv::fastAtan2 (*it_y, *it_x) * azimuth_factor_ + *it_azimuth;
254
+ std::cout << " azimuth_transformation_: " << azimuth_transformation_ << std::endl;
255
+ has_azimuth_transformation_ = true ;
256
+ }
257
+
249
258
while (twist_it != std::end (twist_queue_) - 1 && *it_time_stamp > twist_stamp) {
250
259
++twist_it;
251
260
twist_stamp = rclcpp::Time (twist_it->header .stamp ).seconds ();
@@ -311,14 +320,22 @@ bool DistortionCorrectorComponent::undistortPointCloud(
311
320
undistorted_point = tf2_base_link_to_sensor * undistorted_point;
312
321
}
313
322
323
+ std::cout << " berfore x : " << *it_x << " y : " << *it_y << " azimuth : " << *it_azimuth
324
+ << std::endl;
314
325
*it_x = static_cast <float >(undistorted_point.getX ());
315
326
*it_y = static_cast <float >(undistorted_point.getY ());
316
327
*it_z = static_cast <float >(undistorted_point.getZ ());
317
328
318
329
if (update_azimuth_and_distance_ && need_transform) {
319
330
*it_distance = sqrt (*it_x * *it_x + *it_y * *it_y + *it_z * *it_z);
320
- *it_azimuth = cv::fastAtan2 (*it_y, *it_x) * azimuth_factor_;
331
+ float cartesian_coordinate_azimuth = cv::fastAtan2 (*it_y, *it_x) * azimuth_factor_;
332
+ *it_azimuth = azimuth_transformation_ - cartesian_coordinate_azimuth > 0 .f
333
+ ? azimuth_transformation_ - cartesian_coordinate_azimuth
334
+ : azimuth_transformation_ - cartesian_coordinate_azimuth + 36000 .f ;
321
335
}
336
+ std::cout << " after x : " << *it_x << " y : " << *it_y << " azimuth : " << *it_azimuth
337
+ << std::endl;
338
+
322
339
prev_time_stamp_sec = *it_time_stamp;
323
340
}
324
341
return true ;
0 commit comments