From 3006ea4d838355cb750e7cff8ace73c8a933d8f2 Mon Sep 17 00:00:00 2001 From: Ussama Naal Date: Tue, 29 Oct 2024 18:24:15 -0700 Subject: [PATCH] Update launch files and CHANGELOG --- CHANGELOG.rst | 3 +++ ouster-ros/config/driver_params.yaml | 6 +++++- ouster-ros/config/os_sensor_cloud_image_params.yaml | 1 + ouster-ros/launch/record.composite.launch.xml | 5 +++++ ouster-ros/launch/replay.composite.launch.xml | 5 +++++ ouster-ros/launch/replay_pcap.launch.xml | 5 +++++ ouster-ros/launch/sensor.composite.launch.xml | 5 +++++ ouster-ros/launch/sensor.independent.launch.xml | 5 +++++ ouster-ros/launch/sensor_mtp.launch.xml | 5 +++++ ouster-ros/package.xml | 2 +- 10 files changed, 40 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index d70bb997..8f20829b 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -6,6 +6,9 @@ Changelog ============ * [BUGFIX]: correctly align timestamps to the generated point cloud. * Added support to enable **loop** for pcap replay + other replay config. +* Added a new launch file parameter ``pub_static_tf`` that allows users to turn off braodcast + of the sensor TF transforms. + ouster_ros v0.13.2 ================== diff --git a/ouster-ros/config/driver_params.yaml b/ouster-ros/config/driver_params.yaml index 8f6f5b40..05a0c217 100644 --- a/ouster-ros/config/driver_params.yaml +++ b/ouster-ros/config/driver_params.yaml @@ -56,7 +56,11 @@ ouster/os_driver: # point_cloud_frame[optional]: which frame of reference to use when # generating PointCloud2 or LaserScan messages, select between the values of # lidar_frame and sensor_frame. - point_cloud_frame: os_lidar + point_cloud_frame: os_lidar + # pub_static_tf[optional]: when this flag is set to True, the driver will + # broadcast the TF transforms for the imu/sensor/lidar frames. Prevent the + # driver from broadcasting TF transforms by setting this parameter to False. + pub_static_tf: true # proc_mask[optional]: use any combination of the 4 flags IMG, PCL, IMU and # SCAN to enable or disable their respective messages. proc_mask: IMU|PCL|SCAN|IMG|RAW diff --git a/ouster-ros/config/os_sensor_cloud_image_params.yaml b/ouster-ros/config/os_sensor_cloud_image_params.yaml index 52296c1d..593053f8 100644 --- a/ouster-ros/config/os_sensor_cloud_image_params.yaml +++ b/ouster-ros/config/os_sensor_cloud_image_params.yaml @@ -27,6 +27,7 @@ ouster/os_cloud: lidar_frame: os_lidar imu_frame: os_imu point_cloud_frame: os_lidar + pub_static_tf: true timestamp_mode: '' # this value needs to match os_sensor/timestamp_mode ptp_utc_tai_offset: -37.0 # UTC/TAI offset in seconds to apply when using TIME_FROM_PTP_1588 proc_mask: IMU|PCL|SCAN # pick IMU, PCL, SCAN or any combination of the three options diff --git a/ouster-ros/launch/record.composite.launch.xml b/ouster-ros/launch/record.composite.launch.xml index 0908ada5..d89d3c1f 100644 --- a/ouster-ros/launch/record.composite.launch.xml +++ b/ouster-ros/launch/record.composite.launch.xml @@ -55,6 +55,10 @@ description="which frame to be used when publishing PointCloud2 or LaserScan messages. Choose between the value of sensor_frame or lidar_frame, leaving this value empty would set lidar_frame to be the frame used when publishing these messages."/> + @@ -125,6 +129,7 @@ + diff --git a/ouster-ros/launch/replay.composite.launch.xml b/ouster-ros/launch/replay.composite.launch.xml index 7eba0a55..2d0a99a5 100644 --- a/ouster-ros/launch/replay.composite.launch.xml +++ b/ouster-ros/launch/replay.composite.launch.xml @@ -40,6 +40,10 @@ description="which frame to be used when publishing PointCloud2 or LaserScan messages. Choose between the value of sensor_frame or lidar_frame, leaving this value empty would set lidar_frame to be the frame used when publishing these messages."/> + @@ -87,6 +91,7 @@ + diff --git a/ouster-ros/launch/replay_pcap.launch.xml b/ouster-ros/launch/replay_pcap.launch.xml index 529e884b..9c5a7f3b 100644 --- a/ouster-ros/launch/replay_pcap.launch.xml +++ b/ouster-ros/launch/replay_pcap.launch.xml @@ -36,6 +36,10 @@ description="which frame to be used when publishing PointCloud2 or LaserScan messages. Choose between the value of sensor_frame or lidar_frame, leaving this value empty would set lidar_frame to be the frame used when publishing these messages."/> + @@ -84,6 +88,7 @@ + diff --git a/ouster-ros/launch/sensor.composite.launch.xml b/ouster-ros/launch/sensor.composite.launch.xml index 8d1c40f6..7ffae269 100644 --- a/ouster-ros/launch/sensor.composite.launch.xml +++ b/ouster-ros/launch/sensor.composite.launch.xml @@ -53,6 +53,10 @@ description="which frame to be used when publishing PointCloud2 or LaserScan messages. Choose between the value of sensor_frame or lidar_frame, leaving this value empty would set lidar_frame to be the frame used when publishing these messages."/> + @@ -119,6 +123,7 @@ + diff --git a/ouster-ros/launch/sensor.independent.launch.xml b/ouster-ros/launch/sensor.independent.launch.xml index 21cbeac1..41625bdb 100644 --- a/ouster-ros/launch/sensor.independent.launch.xml +++ b/ouster-ros/launch/sensor.independent.launch.xml @@ -53,6 +53,10 @@ description="which frame to be used when publishing PointCloud2 or LaserScan messages. Choose between the value of sensor_frame or lidar_frame, leaving this value empty would set lidar_frame to be the frame used when publishing these messages."/> + @@ -122,6 +126,7 @@ + diff --git a/ouster-ros/launch/sensor_mtp.launch.xml b/ouster-ros/launch/sensor_mtp.launch.xml index ab721f82..387aec86 100644 --- a/ouster-ros/launch/sensor_mtp.launch.xml +++ b/ouster-ros/launch/sensor_mtp.launch.xml @@ -61,6 +61,10 @@ description="which frame to be used when publishing PointCloud2 or LaserScan messages. Choose between the value of sensor_frame or lidar_frame, leaving this value empty would set lidar_frame to be the frame used when publishing these messages."/> + @@ -117,6 +121,7 @@ + diff --git a/ouster-ros/package.xml b/ouster-ros/package.xml index a2a1bd15..825707e9 100644 --- a/ouster-ros/package.xml +++ b/ouster-ros/package.xml @@ -2,7 +2,7 @@ ouster_ros - 0.13.3 + 0.13.4 Ouster ROS2 driver ouster developers BSD