diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 072d565a461fc..683ab6ff70df7 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -406,7 +406,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /sensing/lidar/concatenated/pointcloud Use Fixed Frame: false Use rainbow: true @@ -439,7 +439,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /sensing/lidar/no_ground/pointcloud Use Fixed Frame: true Use rainbow: true diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index a13afd6504f46..d18d4779c7fc2 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index a13afd6504f46..d18d4779c7fc2 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 0b333fa9c993f..040137f2b45c6 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -265,6 +265,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/outlier_filtered/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index e68a57ecb229c..227146c5b7af5 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -131,6 +131,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index 3d84321720bda..2acaa896a15a3 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], ) diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index a13afd6504f46..d18d4779c7fc2 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -129,6 +129,9 @@ def launch_setup(context, *args, **kwargs): "input_topic": "/sensing/lidar/top/rectified/pointcloud", "output_topic": "/sensing/lidar/pointcloud", "type": "sensor_msgs/msg/PointCloud2", + "history": "keep_last", + "depth": 5, + "reliability": "best_effort", 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }], )