Skip to content

Commit

Permalink
Add a parameter to enable/disable broadcast of sensor transfroms
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Oct 30, 2024
1 parent 7a23879 commit 83af8d4
Show file tree
Hide file tree
Showing 12 changed files with 61 additions and 16 deletions.
2 changes: 2 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@ 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 uers to turn off the broadcast
of sensor TF transforms.


ouster_ros v0.13.0
Expand Down
5 changes: 5 additions & 0 deletions launch/common.launch
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@
<arg name="imu_frame" doc="
sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" doc="
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.."/>
<arg name="pub_static_tf" doc="
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."/>
Expand Down Expand Up @@ -56,6 +60,7 @@
<param name="~/lidar_frame" value="$(arg lidar_frame)"/>
<param name="~/imu_frame" value="$(arg imu_frame)"/>
<param name="~/point_cloud_frame" value="$(arg point_cloud_frame)"/>
<param name="~/pub_static_tf" value="$(arg pub_static_tf)"/>
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
<param name="~/dynamic_transforms_broadcast" type="bool"
value="$(arg dynamic_transforms_broadcast)"/>
Expand Down
5 changes: 5 additions & 0 deletions launch/driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,10 @@
doc="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."/>
<arg name="pub_static_tf" default="true" doc="
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."/>

<arg name="no_bond" default="false"
doc="request no bond setup when nodelets are created"/>
Expand Down Expand Up @@ -119,6 +123,7 @@
<param name="~/lidar_frame" value="$(arg lidar_frame)"/>
<param name="~/imu_frame" value="$(arg imu_frame)"/>
<param name="~/point_cloud_frame" value="$(arg point_cloud_frame)"/>
<param name="~/pub_static_tf" value="$(arg pub_static_tf)"/>
<param name="~/proc_mask" value="$(arg proc_mask)"/>
<param name="~/scan_ring" value="$(arg scan_ring)"/>
<param name="~/point_type" value="$(arg point_type)"/>
Expand Down
5 changes: 5 additions & 0 deletions launch/record.launch
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,10 @@
doc="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."/>
<arg name="pub_static_tf" default="true" doc="
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."/>

<arg name="dynamic_transforms_broadcast" default="false"
doc="static or dynamic transforms broadcast"/>
Expand Down Expand Up @@ -123,6 +127,7 @@
<arg name="lidar_frame" value="$(arg lidar_frame)"/>
<arg name="imu_frame" value="$(arg imu_frame)"/>
<arg name="point_cloud_frame" value="$(arg point_cloud_frame)"/>
<aeg name="pub_static_tf" value="$(arg pub_static_tf)"/>
<arg name="timestamp_mode" value="$(arg timestamp_mode)"/>
<arg name="ptp_utc_tai_offset" value="$(arg ptp_utc_tai_offset)"/>
<arg name="dynamic_transforms_broadcast"
Expand Down
5 changes: 5 additions & 0 deletions launch/replay.launch
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,10 @@
doc="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."/>
<arg name="pub_static_tf" default="true" doc="
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."/>

<arg name="dynamic_transforms_broadcast" default="false"
doc="static or dynamic transforms broadcast"/>
Expand Down Expand Up @@ -98,6 +102,7 @@
<arg name="lidar_frame" value="$(arg lidar_frame)"/>
<arg name="imu_frame" value="$(arg imu_frame)"/>
<arg name="point_cloud_frame" value="$(arg point_cloud_frame)"/>
<arg name="pub_static_tf" value="$(arg pub_static_tf)"/>
<arg name="timestamp_mode" value="$(arg timestamp_mode)"/>
<arg name="ptp_utc_tai_offset" value="$(arg ptp_utc_tai_offset)"/>
<arg name="dynamic_transforms_broadcast"
Expand Down
5 changes: 5 additions & 0 deletions launch/replay_pcap.launch
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,10 @@
doc="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."/>
<arg name="pub_static_tf" default="true" doc="
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."/>

<arg name="dynamic_transforms_broadcast" default="false"
doc="static or dynamic transforms broadcast"/>
Expand Down Expand Up @@ -94,6 +98,7 @@
<arg name="lidar_frame" value="$(arg lidar_frame)"/>
<arg name="imu_frame" value="$(arg imu_frame)"/>
<arg name="point_cloud_frame" value="$(arg point_cloud_frame)"/>
<arg name="pub_static_tf" value="$(arg pub_static_tf)"/>
<arg name="timestamp_mode" value="$(arg timestamp_mode)"/>
<arg name="ptp_utc_tai_offset" value="$(arg ptp_utc_tai_offset)"/>
<arg name="dynamic_transforms_broadcast"
Expand Down
5 changes: 5 additions & 0 deletions launch/sensor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,10 @@
doc="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."/>
<arg name="pub_static_tf" default="true" doc="
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."/>

<arg name="no_bond" default="false"
doc="request no bond setup when nodelets are created"/>
Expand Down Expand Up @@ -140,6 +144,7 @@
<arg name="lidar_frame" value="$(arg lidar_frame)"/>
<arg name="imu_frame" value="$(arg imu_frame)"/>
<arg name="point_cloud_frame" value="$(arg point_cloud_frame)"/>
<arg name="pub_static_tf" value="$(arg pub_static_tf)"/>
<arg name="timestamp_mode" value="$(arg timestamp_mode)"/>
<arg name="ptp_utc_tai_offset" value="$(arg ptp_utc_tai_offset)"/>
<arg name="_no_bond" value="$(arg _no_bond)"/>
Expand Down
5 changes: 5 additions & 0 deletions launch/sensor_mtp.launch
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,10 @@
doc="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."/>
<arg name="pub_static_tf" default="true" doc="
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."/>

<arg name="no_bond" default="false"
doc="request no bond setup when nodelets are created"/>
Expand Down Expand Up @@ -146,6 +150,7 @@
<arg name="lidar_frame" value="$(arg lidar_frame)"/>
<arg name="imu_frame" value="$(arg imu_frame)"/>
<arg name="point_cloud_frame" value="$(arg point_cloud_frame)"/>
<arg name="pub_static_tf" value="$(arg pub_static_tf)"/>
<arg name="timestamp_mode" value="$(arg timestamp_mode)"/>
<arg name="ptp_utc_tai_offset" value="$(arg ptp_utc_tai_offset)"/>
<arg name="_no_bond" value="$(arg _no_bond)"/>
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>ouster_ros</name>
<version>0.13.1</version>
<version>0.13.2</version>
<description>Ouster ROS driver</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license file="LICENSE">BSD</license>
Expand Down
30 changes: 16 additions & 14 deletions src/os_cloud_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,20 +76,22 @@ class OusterCloud : public nodelet::Nodelet {
dynamic_transforms_rate = 1.0;
}

if (!dynamic_transforms) {
NODELET_INFO("OusterCloud: using static transforms broadcast");
tf_bcast.broadcast_transforms(info);
} else {
NODELET_INFO_STREAM(
"OusterCloud: dynamic transforms broadcast enabled with "
"broadcast rate of: "
<< dynamic_transforms_rate << " Hz");
timer_.stop();
timer_ = getNodeHandle().createTimer(
ros::Duration(1.0 / dynamic_transforms_rate),
[this, info](const ros::TimerEvent&) {
tf_bcast.broadcast_transforms(info, last_msg_ts);
});
if (tf_bcast.publish_static_tf()) {
if (!dynamic_transforms) {
NODELET_INFO("OusterCloud: using static transforms broadcast");
tf_bcast.broadcast_transforms(info);
} else {
NODELET_INFO_STREAM(
"OusterCloud: dynamic transforms broadcast enabled with "
"broadcast rate of: "
<< dynamic_transforms_rate << " Hz");
timer_.stop();
timer_ = getNodeHandle().createTimer(
ros::Duration(1.0 / dynamic_transforms_rate),
[this, info](const ros::TimerEvent&) {
tf_bcast.broadcast_transforms(info, last_msg_ts);
});
}
}

create_handlers(info);
Expand Down
4 changes: 3 additions & 1 deletion src/os_driver_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,9 @@ class OusterDriver : public OusterSensor {
// for OusterDriver we are going to always assume static broadcast
// at least for now
tf_bcast.parse_parameters(getPrivateNodeHandle());
tf_bcast.broadcast_transforms(info);
if (tf_bcast.publish_static_tf()) {
tf_bcast.broadcast_transforms(info);
}
create_handlers();
}

Expand Down
4 changes: 4 additions & 0 deletions src/os_transforms_broadcaster.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ class OusterTransformsBroadcaster {
lidar_frame = pnh.param("lidar_frame", std::string{"os_lidar"});
imu_frame = pnh.param("imu_frame", std::string{"os_imu"});
point_cloud_frame = pnh.param("point_cloud_frame", std::string{});
pub_static_tf = pnh.param("pub_static_tf", true);

if (!is_arg_set(sensor_frame) || !is_arg_set(lidar_frame) ||
!is_arg_set(imu_frame)) {
Expand Down Expand Up @@ -100,6 +101,8 @@ class OusterTransformsBroadcaster {
return point_cloud_frame == sensor_frame;
}

bool publish_static_tf() const { return pub_static_tf; }

private:
std::string node_name;
tf2_ros::StaticTransformBroadcaster static_tf_bcast;
Expand All @@ -108,6 +111,7 @@ class OusterTransformsBroadcaster {
std::string lidar_frame;
std::string sensor_frame;
std::string point_cloud_frame;
bool pub_static_tf;
};

} // namespace ouster_ros

0 comments on commit 83af8d4

Please sign in to comment.