Skip to content

Commit

Permalink
feat(velodyne_node_container): use distortion_corrector
Browse files Browse the repository at this point in the history
Signed-off-by: 1222-takeshi <[email protected]>
  • Loading branch information
1222-takeshi committed Feb 26, 2024
1 parent b02dc5e commit 34b87e3
Show file tree
Hide file tree
Showing 2 changed files with 42 additions and 42 deletions.
42 changes: 21 additions & 21 deletions aip_x1_1_launch/launch/velodyne_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,35 +104,35 @@ def create_parameter_dict(*args):
)
)

nodes.append(
ComposableNode(
package="velodyne_pointcloud",
plugin="velodyne_pointcloud::Interpolate",
name="velodyne_interpolate_node",
remappings=[
("velodyne_points_ex", "self_cropped/pointcloud_ex"),
("velodyne_points_interpolate", "rectified/pointcloud"),
("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"),
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)

# nodes.append(
# ComposableNode(
# package="pointcloud_preprocessor",
# plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
# name="distortion_corrector_node",
# package="velodyne_pointcloud",
# plugin="velodyne_pointcloud::Interpolate",
# name="velodyne_interpolate_node",
# remappings=[
# ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
# ("~/input/imu", "/sensing/imu/imu_data"),
# ("~/input/pointcloud", "self_cropped/pointcloud_ex"),
# ("~/output/pointcloud", "rectified/pointcloud_ex"),
# ("velodyne_points_ex", "self_cropped/pointcloud_ex"),
# ("velodyne_points_interpolate", "rectified/pointcloud"),
# ("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"),
# ],
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
# )
# )

nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
name="distortion_corrector_node",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("~/input/imu", "/sensing/imu/imu_data"),
("~/input/pointcloud", "self_cropped/pointcloud_ex"),
("~/output/pointcloud", "rectified/pointcloud_ex"),
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)

nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
Expand Down
42 changes: 21 additions & 21 deletions aip_x1_launch/launch/velodyne_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,35 +104,35 @@ def create_parameter_dict(*args):
)
)

# nodes.append(
# ComposableNode(
# package="pointcloud_preprocessor",
# plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
# name="distortion_corrector_node",
# remappings=[
# ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
# ("~/input/imu", "/sensing/imu/imu_data"),
# ("~/input/pointcloud", "self_cropped/pointcloud_ex"),
# ("~/output/pointcloud", "rectified/pointcloud_ex"),
# ],
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
# )
# )

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/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("~/input/imu", "/sensing/imu/imu_data"),
("~/input/pointcloud", "self_cropped/pointcloud_ex"),
("~/output/pointcloud", "rectified/pointcloud_ex"),
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)

# nodes.append(
# ComposableNode(
# package="velodyne_pointcloud",
# plugin="velodyne_pointcloud::Interpolate",
# name="velodyne_interpolate_node",
# remappings=[
# ("velodyne_points_ex", "self_cropped/pointcloud_ex"),
# ("velodyne_points_interpolate", "rectified/pointcloud"),
# ("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"),
# ],
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
# )
# )

nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
Expand Down

0 comments on commit 34b87e3

Please sign in to comment.