From ab81c478cb325c9a2b30c7c13fa57bd43116948c Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 13 Nov 2023 07:54:38 +0000 Subject: [PATCH] style(pre-commit): autofix --- sensing/pointcloud_preprocessor/docs/distortion-corrector.md | 5 +++-- .../distortion_corrector/distortion_corrector.hpp | 2 +- .../src/distortion_corrector/distortion_corrector.cpp | 2 +- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/sensing/pointcloud_preprocessor/docs/distortion-corrector.md b/sensing/pointcloud_preprocessor/docs/distortion-corrector.md index 905b452e5c497..03b04bf0811e9 100644 --- a/sensing/pointcloud_preprocessor/docs/distortion-corrector.md +++ b/sensing/pointcloud_preprocessor/docs/distortion-corrector.md @@ -43,7 +43,8 @@ $ ExactPointTime = TimeStamp + TimeOffset $ | ----------------------------- | ------ | ------------- | ----------------------------------------------------------- | | `timestamp_field_name` | string | "time_stamp" | time stamp field name | | `use_imu` | bool | true | use gyroscope for yaw rate if true, else use vehicle status | -| `update_azimuth_and_distance`| bool | false | update the azimuth and distance based on undistorted xyz | +| `update_azimuth_and_distance` | bool | false | update the azimuth and distance based on undistorted xyz | ## Assumptions / Known limits -When setting the parameter `update_azimuth_and_distance` to True, the node will calculate the azimuth value based on the undistorted XYZ by using atan2, which will return the azimuth value with the coordinate system that the x-axis is 0 degrees and the y-axis is 90 degrees. Please make sure the frame coordinates are same as the coordinate system mentioned in the above. For autoware user, the frame_id of input pointcloud is base_link, which the coordinate system is same as the coordinate system mentioned above, therefore it won't casue any issues. Also note that by setting the parameter `update_azimuth_and_distance` to True, the time will incrase around 13%. \ No newline at end of file + +When setting the parameter `update_azimuth_and_distance` to True, the node will calculate the azimuth value based on the undistorted XYZ by using atan2, which will return the azimuth value with the coordinate system that the x-axis is 0 degrees and the y-axis is 90 degrees. Please make sure the frame coordinates are same as the coordinate system mentioned in the above. For autoware user, the frame_id of input pointcloud is base_link, which the coordinate system is same as the coordinate system mentioned above, therefore it won't casue any issues. Also note that by setting the parameter `update_azimuth_and_distance` to True, the time will incrase around 13%. diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index f34498201fd1c..cab62613cc4a7 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -36,13 +36,13 @@ #include // Include tier4 autoware utils +#include #include #include #include #include #include -#include namespace pointcloud_preprocessor { diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 0abaa4da45c08..4c107c41970a3 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -319,4 +319,4 @@ bool DistortionCorrectorComponent::undistortPointCloud( } // namespace pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DistortionCorrectorComponent) \ No newline at end of file +RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DistortionCorrectorComponent)