Skip to content

Commit f3cc66f

Browse files
committed
wait until fix
Signed-off-by: vividf <yihsiang.fang@tier4.jp>
1 parent 55682dd commit f3cc66f

File tree

2 files changed

+22
-3
lines changed

2 files changed

+22
-3
lines changed

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,9 @@ class DistortionCorrectorComponent : public rclcpp::Node
8383
std::string time_stamp_field_name_;
8484
bool use_imu_;
8585
bool update_azimuth_and_distance_;
86-
float azimuth_factor_ = 100.0;
86+
bool has_azimuth_transformation_;
87+
float azimuth_transformation_;
88+
float azimuth_factor_{100.0};
8789
};
8890

8991
} // namespace pointcloud_preprocessor

sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp

+19-2
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt
3939
// Parameter
4040
time_stamp_field_name_ = declare_parameter("time_stamp_field_name", "time_stamp");
4141
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);
4343

4444
// Publisher
4545
undistorted_points_pub_ =
@@ -246,6 +246,15 @@ bool DistortionCorrectorComponent::undistortPointCloud(
246246
bool need_transform = points.header.frame_id != base_link_frame_;
247247

248248
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+
249258
while (twist_it != std::end(twist_queue_) - 1 && *it_time_stamp > twist_stamp) {
250259
++twist_it;
251260
twist_stamp = rclcpp::Time(twist_it->header.stamp).seconds();
@@ -311,14 +320,22 @@ bool DistortionCorrectorComponent::undistortPointCloud(
311320
undistorted_point = tf2_base_link_to_sensor * undistorted_point;
312321
}
313322

323+
std::cout << "berfore x : " << *it_x << " y : " << *it_y << " azimuth : " << *it_azimuth
324+
<< std::endl;
314325
*it_x = static_cast<float>(undistorted_point.getX());
315326
*it_y = static_cast<float>(undistorted_point.getY());
316327
*it_z = static_cast<float>(undistorted_point.getZ());
317328

318329
if (update_azimuth_and_distance_ && need_transform) {
319330
*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;
321335
}
336+
std::cout << "after x : " << *it_x << " y : " << *it_y << " azimuth : " << *it_azimuth
337+
<< std::endl;
338+
322339
prev_time_stamp_sec = *it_time_stamp;
323340
}
324341
return true;

0 commit comments

Comments
 (0)