From 3d82e799820b67ae3e2c1421bdd57634009589bd Mon Sep 17 00:00:00 2001
From: Ussama Naal <606033+Samahu@users.noreply.github.com>
Date: Wed, 15 Nov 2023 12:39:15 -0800
Subject: [PATCH] SW-5466: Support Velodyne point type in the ROS driver
amendments (#254)
* Add support to control point_type through launch.xml files +
* Add a note to CHANGELOG about the breaking change for ptp/utc time offset
---
CHANGELOG.rst | 2 ++
ouster-ros/launch/record.composite.launch.xml | 10 ++++++++++
ouster-ros/launch/replay.composite.launch.xml | 10 ++++++++++
ouster-ros/launch/sensor.composite.launch.xml | 10 ++++++++++
ouster-ros/launch/sensor.independent.launch.xml | 10 ++++++++++
ouster-ros/launch/sensor_mtp.launch.xml | 10 ++++++++++
ouster-ros/package.xml | 2 +-
ouster-sensor-msgs/package.xml | 2 +-
8 files changed, 54 insertions(+), 2 deletions(-)
diff --git a/CHANGELOG.rst b/CHANGELOG.rst
index 0fa74acf..840ebf04 100644
--- a/CHANGELOG.rst
+++ b/CHANGELOG.rst
@@ -8,6 +8,8 @@ Changelog
* introduced a new launch file parameter ``ptp_utc_tai_offset`` which represent offset in seconds
to be applied to all ROS messages the driver generates when ``TIME_FROM_PTP_1588`` timestamp mode
is used.
+ * [BREAKING]: the default value of ``ptp_utc_tai_offset`` is set to ``-37.0``. To retain the same
+ time offset for an existing system, users need to set ``ptp_utc_tai_offset`` to ``0.0``.
* fix: destagger columns timestamp when generating destaggered point clouds.
* shutdown the driver when unable to connect to the sensor on startup
* breaking: rename ouster_msgs to ouster_sensor_msgs
diff --git a/ouster-ros/launch/record.composite.launch.xml b/ouster-ros/launch/record.composite.launch.xml
index 51196283..39ebac82 100644
--- a/ouster-ros/launch/record.composite.launch.xml
+++ b/ouster-ros/launch/record.composite.launch.xml
@@ -67,6 +67,15 @@
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>
+
+
@@ -93,6 +102,7 @@
+
diff --git a/ouster-ros/launch/replay.composite.launch.xml b/ouster-ros/launch/replay.composite.launch.xml
index 649ba6b6..e0e4e20b 100644
--- a/ouster-ros/launch/replay.composite.launch.xml
+++ b/ouster-ros/launch/replay.composite.launch.xml
@@ -47,6 +47,15 @@
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>
+
+
@@ -64,6 +73,7 @@
+
diff --git a/ouster-ros/launch/sensor.composite.launch.xml b/ouster-ros/launch/sensor.composite.launch.xml
index a96642f7..758e6479 100644
--- a/ouster-ros/launch/sensor.composite.launch.xml
+++ b/ouster-ros/launch/sensor.composite.launch.xml
@@ -63,6 +63,15 @@
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>
+
+
@@ -84,6 +93,7 @@
+
diff --git a/ouster-ros/launch/sensor.independent.launch.xml b/ouster-ros/launch/sensor.independent.launch.xml
index 6c1bf364..5222ce8c 100644
--- a/ouster-ros/launch/sensor.independent.launch.xml
+++ b/ouster-ros/launch/sensor.independent.launch.xml
@@ -65,6 +65,15 @@
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>
+
+
@@ -90,6 +99,7 @@
+
diff --git a/ouster-ros/launch/sensor_mtp.launch.xml b/ouster-ros/launch/sensor_mtp.launch.xml
index a7da2b7a..a89fc875 100644
--- a/ouster-ros/launch/sensor_mtp.launch.xml
+++ b/ouster-ros/launch/sensor_mtp.launch.xml
@@ -71,6 +71,15 @@
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>
+
+
@@ -92,6 +101,7 @@
+
diff --git a/ouster-ros/package.xml b/ouster-ros/package.xml
index 033faa2d..b6796fbd 100644
--- a/ouster-ros/package.xml
+++ b/ouster-ros/package.xml
@@ -2,7 +2,7 @@
ouster_ros
- 0.11.1
+ 0.11.2
Ouster ROS2 driver
ouster developers
BSD
diff --git a/ouster-sensor-msgs/package.xml b/ouster-sensor-msgs/package.xml
index 5c46bfd2..22e829d1 100644
--- a/ouster-sensor-msgs/package.xml
+++ b/ouster-sensor-msgs/package.xml
@@ -2,7 +2,7 @@
ouster_sensor_msgs
- 0.11.1
+ 0.11.2
ouster_ros message and service definitions
ouster developers
BSD