Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Nov 13, 2023
1 parent 447a71d commit ab81c47
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 4 deletions.
5 changes: 3 additions & 2 deletions sensing/pointcloud_preprocessor/docs/distortion-corrector.md
Original file line number Diff line number Diff line change
Expand Up @@ -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%.

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%.

Check warning on line 50 in sensing/pointcloud_preprocessor/docs/distortion-corrector.md

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (casue)

Check warning on line 50 in sensing/pointcloud_preprocessor/docs/distortion-corrector.md

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (incrase)

Check warning on line 50 in sensing/pointcloud_preprocessor/docs/distortion-corrector.md

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (casue)

Check warning on line 50 in sensing/pointcloud_preprocessor/docs/distortion-corrector.md

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (incrase)
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,13 @@
#include <tf2_ros/transform_listener.h>

// Include tier4 autoware utils
#include <opencv2/opencv.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>

#include <deque>
#include <memory>
#include <string>
#include <opencv2/opencv.hpp>

namespace pointcloud_preprocessor
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -319,4 +319,4 @@ bool DistortionCorrectorComponent::undistortPointCloud(
} // namespace pointcloud_preprocessor

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DistortionCorrectorComponent)
RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DistortionCorrectorComponent)

0 comments on commit ab81c47

Please sign in to comment.