diff --git a/aip_x1_launch/launch/velodyne_node_container.launch.py b/aip_x1_launch/launch/velodyne_node_container.launch.py index ef1065ba..dce742b5 100644 --- a/aip_x1_launch/launch/velodyne_node_container.launch.py +++ b/aip_x1_launch/launch/velodyne_node_container.launch.py @@ -106,13 +106,13 @@ def create_parameter_dict(*args): nodes.append( ComposableNode( - package="velodyne_pointcloud", - plugin="velodyne_pointcloud::Interpolate", - name="velodyne_interpolate_node", + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::DistortionCorrectorComponent", + name="distortion_corrector_node", remappings=[ - ("velodyne_points_ex", "self_cropped/pointcloud_ex"), - ("velodyne_points_interpolate", "rectified/pointcloud"), - ("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"), + ("~/input/pointcloud", "self_cropped/pointcloud_ex"), + ("~/input/velocity_report", "/vehicle/status/velocity_report"), + ("~/output/pointcloud", "rectified/pointcloud_ex"), ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) diff --git a/common_sensor_launch/launch/velodyne_node_container.launch.py b/common_sensor_launch/launch/velodyne_node_container.launch.py index 205dab89..e3172232 100644 --- a/common_sensor_launch/launch/velodyne_node_container.launch.py +++ b/common_sensor_launch/launch/velodyne_node_container.launch.py @@ -135,13 +135,13 @@ def create_parameter_dict(*args): nodes.append( ComposableNode( - package="velodyne_pointcloud", - plugin="velodyne_pointcloud::Interpolate", - name="velodyne_interpolate_node", + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::DistortionCorrectorComponent", + name="distortion_corrector_node", remappings=[ - ("velodyne_points_ex", "mirror_cropped/pointcloud_ex"), - ("velodyne_points_interpolate", "rectified/pointcloud"), - ("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"), + ("~/input/pointcloud", "mirror_cropped/pointcloud_ex"), + ("~/input/velocity_report", "/vehicle/status/velocity_report"), + ("~/output/pointcloud", "rectified/pointcloud_ex"), ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], )