diff --git a/aip_x2_gen2_launch/launch/gnss.launch.xml b/aip_x2_gen2_launch/launch/gnss.launch.xml index 8ccd477c..7f9e5d3f 100644 --- a/aip_x2_gen2_launch/launch/gnss.launch.xml +++ b/aip_x2_gen2_launch/launch/gnss.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/aip_x2_gen2_launch/launch/imu.launch.xml b/aip_x2_gen2_launch/launch/imu.launch.xml index a2c0c80d..fd07632c 100644 --- a/aip_x2_gen2_launch/launch/imu.launch.xml +++ b/aip_x2_gen2_launch/launch/imu.launch.xml @@ -23,13 +23,13 @@ - + - + diff --git a/aip_x2_gen2_launch/launch/nebula_node_container.launch.py b/aip_x2_gen2_launch/launch/nebula_node_container.launch.py index d228e11c..181b32b3 100644 --- a/aip_x2_gen2_launch/launch/nebula_node_container.launch.py +++ b/aip_x2_gen2_launch/launch/nebula_node_container.launch.py @@ -143,8 +143,8 @@ def str2vector(string): cropbox_parameters["max_z"] = vehicle_info["max_height_offset"] self_crop_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_self", remappings=[ ("input", "pointcloud_raw_ex"), @@ -166,8 +166,8 @@ def str2vector(string): ) right_mirror_crop_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_mirror_right", remappings=[ ("input", "self_cropped/pointcloud_ex"), @@ -188,8 +188,8 @@ def str2vector(string): ) left_mirror_crop_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_mirror_left", remappings=[ ("input", "right_mirror_cropped/pointcloud_ex"), @@ -200,8 +200,8 @@ def str2vector(string): ) undistort_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::DistortionCorrectorComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::DistortionCorrectorComponent", name="distortion_corrector_node", remappings=[ ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), @@ -214,8 +214,8 @@ def str2vector(string): ) ring_outlier_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::RingOutlierFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent", name="ring_outlier_filter", remappings=[ ("input", "rectified/pointcloud_ex"), @@ -225,8 +225,8 @@ def str2vector(string): ) dual_return_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::DualReturnOutlierFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::DualReturnOutlierFilterComponent", name="dual_return_filter", remappings=[ ("input", "rectified/pointcloud_ex"), @@ -245,8 +245,8 @@ def str2vector(string): distance_range = str2vector(context.perform_substitution(LaunchConfiguration("distance_range"))) blockage_diag_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::BlockageDiagComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::BlockageDiagComponent", name="blockage_return_diag", remappings=[ ("input", "pointcloud_raw_ex"), diff --git a/aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py b/aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py index ef03f232..0775e3a2 100644 --- a/aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py @@ -27,8 +27,8 @@ def launch_setup(context, *args, **kwargs): # set concat filter as a component concat_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", name="concatenate_data", remappings=[ ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), diff --git a/aip_x2_gen2_launch/launch/radar.launch.xml b/aip_x2_gen2_launch/launch/radar.launch.xml index 5fc16689..d793d8de 100644 --- a/aip_x2_gen2_launch/launch/radar.launch.xml +++ b/aip_x2_gen2_launch/launch/radar.launch.xml @@ -32,7 +32,7 @@ - + @@ -62,7 +62,7 @@ - + @@ -92,7 +92,7 @@ - + @@ -122,7 +122,7 @@ - + @@ -152,7 +152,7 @@ - + @@ -182,7 +182,7 @@ - + @@ -194,7 +194,7 @@ - + diff --git a/aip_x2_gen2_launch/launch/sensing.launch.xml b/aip_x2_gen2_launch/launch/sensing.launch.xml index ec9adc0e..8000211f 100644 --- a/aip_x2_gen2_launch/launch/sensing.launch.xml +++ b/aip_x2_gen2_launch/launch/sensing.launch.xml @@ -30,7 +30,7 @@ - + diff --git a/aip_x2_gen2_launch/package.xml b/aip_x2_gen2_launch/package.xml index 2743c6a8..12b96ff0 100644 --- a/aip_x2_gen2_launch/package.xml +++ b/aip_x2_gen2_launch/package.xml @@ -12,15 +12,15 @@ common_sensor_launch dummy_diag_publisher - gnss_poser - imu_corrector - pointcloud_preprocessor + autoware_gnss_poser + autoware_imu_corrector + autoware_pointcloud_preprocessor septentrio_gnss_driver tamagawa_imu_driver topic_tools ublox_gps usb_cam - vehicle_velocity_converter + autoware_vehicle_velocity_converter ament_lint_auto autoware_lint_common