From 4361969cbd03e7667531d11fd2a508aafd53117d Mon Sep 17 00:00:00 2001 From: Adam Aposhian Date: Thu, 27 Apr 2023 16:31:19 -0600 Subject: [PATCH 1/3] use separate params for tf frames --- ouster-ros/config/parameters.yaml | 4 +++- ouster-ros/launch/record.composite.launch.xml | 8 ++++++-- ouster-ros/launch/replay.composite.launch.xml | 8 ++++++-- ouster-ros/launch/sensor.composite.launch.xml | 8 ++++++-- ouster-ros/launch/sensor.independent.launch.xml | 8 ++++++-- ouster-ros/launch/sensor_mtp.launch.xml | 8 ++++++-- ouster-ros/src/os_cloud_node.cpp | 13 ++++++------- 7 files changed, 39 insertions(+), 18 deletions(-) diff --git a/ouster-ros/config/parameters.yaml b/ouster-ros/config/parameters.yaml index 44189e15..9c0b7590 100644 --- a/ouster-ros/config/parameters.yaml +++ b/ouster-ros/config/parameters.yaml @@ -12,5 +12,7 @@ ouster/os_sensor: imu_port: 0 ouster/os_cloud: ros__parameters: - tf_prefix: '' + sensor_frame: '' # Frame of physical sensor + lidar_frame: '' # Frame of lidar scans + imu_frame: '' # Frame of IMU data timestamp_mode: '' diff --git a/ouster-ros/launch/record.composite.launch.xml b/ouster-ros/launch/record.composite.launch.xml index d219d093..aab8335b 100644 --- a/ouster-ros/launch/record.composite.launch.xml +++ b/ouster-ros/launch/record.composite.launch.xml @@ -41,7 +41,9 @@ description="whether to run a rviz"/> - + + + @@ -59,7 +61,9 @@ - + + + diff --git a/ouster-ros/launch/replay.composite.launch.xml b/ouster-ros/launch/replay.composite.launch.xml index 2941ba30..6732a671 100644 --- a/ouster-ros/launch/replay.composite.launch.xml +++ b/ouster-ros/launch/replay.composite.launch.xml @@ -18,7 +18,9 @@ description="whether to run a rviz"/> - + + + @@ -29,7 +31,9 @@ - + + + diff --git a/ouster-ros/launch/sensor.composite.launch.xml b/ouster-ros/launch/sensor.composite.launch.xml index cd2965c1..d50b4dfc 100644 --- a/ouster-ros/launch/sensor.composite.launch.xml +++ b/ouster-ros/launch/sensor.composite.launch.xml @@ -39,7 +39,9 @@ description="whether to run a rviz"/> - + + + @@ -57,7 +59,9 @@ - + + + diff --git a/ouster-ros/launch/sensor.independent.launch.xml b/ouster-ros/launch/sensor.independent.launch.xml index a40c09f7..64d39c40 100644 --- a/ouster-ros/launch/sensor.independent.launch.xml +++ b/ouster-ros/launch/sensor.independent.launch.xml @@ -39,7 +39,9 @@ description="whether to run a rviz"/> - + + + @@ -56,7 +58,9 @@ - + + + diff --git a/ouster-ros/launch/sensor_mtp.launch.xml b/ouster-ros/launch/sensor_mtp.launch.xml index 7fe115f7..f604a9d9 100644 --- a/ouster-ros/launch/sensor_mtp.launch.xml +++ b/ouster-ros/launch/sensor_mtp.launch.xml @@ -47,7 +47,9 @@ description="whether to run a rviz"/> - + + + @@ -65,7 +67,9 @@ - + + + diff --git a/ouster-ros/src/os_cloud_node.cpp b/ouster-ros/src/os_cloud_node.cpp index d4a451c4..05960b3d 100644 --- a/ouster-ros/src/os_cloud_node.cpp +++ b/ouster-ros/src/os_cloud_node.cpp @@ -91,17 +91,16 @@ class OusterCloud : public OusterProcessingNodeBase { } void declare_parameters() { - declare_parameter("tf_prefix"); + declare_parameter("lidar_frame"); + declare_parameter("sensor_frame"); + declare_parameter("imu_frame"); declare_parameter("timestamp_mode"); } void parse_parameters() { - auto tf_prefix = get_parameter("tf_prefix").as_string(); - if (is_arg_set(tf_prefix) && tf_prefix.back() != '/') - tf_prefix.append("/"); - sensor_frame = tf_prefix + "os_sensor"; - imu_frame = tf_prefix + "os_imu"; - lidar_frame = tf_prefix + "os_lidar"; + sensor_frame = get_parameter("sensor_frame").as_string(); + imu_frame = get_parameter("imu_frame").as_string(); + lidar_frame = get_parameter("lidar_frame").as_string(); auto timestamp_mode_arg = get_parameter("timestamp_mode").as_string(); use_ros_time = timestamp_mode_arg == "TIME_FROM_ROS_TIME"; } From 09b64150dcc9eb03c94882d757f793babe1f2eb0 Mon Sep 17 00:00:00 2001 From: Adam Aposhian Date: Thu, 27 Apr 2023 16:40:44 -0600 Subject: [PATCH 2/3] send static transforms once --- ouster-ros/src/os_cloud_node.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/ouster-ros/src/os_cloud_node.cpp b/ouster-ros/src/os_cloud_node.cpp index 05960b3d..c3261a06 100644 --- a/ouster-ros/src/os_cloud_node.cpp +++ b/ouster-ros/src/os_cloud_node.cpp @@ -14,7 +14,7 @@ #include #include -#include +#include #include #include @@ -117,6 +117,7 @@ class OusterCloud : public OusterProcessingNodeBase { RCLCPP_INFO(get_logger(), "OusterCloud: retrieved new sensor metadata!"); info = sensor::parse_metadata(metadata_msg->data); + send_static_transforms(); n_returns = get_n_returns(); create_lidarscan_objects(); compute_scan_ts = [this](const auto& ts_v) { @@ -126,6 +127,13 @@ class OusterCloud : public OusterProcessingNodeBase { create_subscriptions(); } + void send_static_transforms() { + tf_bcast.sendTransform(ouster_ros::transform_to_tf_msg( + info.lidar_to_sensor_transform, sensor_frame, lidar_frame, now())); + tf_bcast.sendTransform(ouster_ros::transform_to_tf_msg( + info.imu_to_sensor_transform, sensor_frame, imu_frame, now())); + } + void create_lidarscan_objects() { // The ouster_ros drive currently only uses single precision when it // produces the point cloud. So it isn't of a benefit to compute point @@ -195,9 +203,6 @@ class OusterCloud : public OusterProcessingNodeBase { pc_msg.header.frame_id = sensor_frame; lidar_pubs[i]->publish(pc_msg); } - - tf_bcast.sendTransform(ouster_ros::transform_to_tf_msg( - info.lidar_to_sensor_transform, sensor_frame, lidar_frame, msg_ts)); } uint64_t impute_value(int last_scan_last_nonzero_idx, @@ -311,8 +316,6 @@ class OusterCloud : public OusterProcessingNodeBase { auto imu_msg = ouster_ros::packet_to_imu_msg(*packet, msg_ts, imu_frame, pf); imu_pub->publish(imu_msg); - tf_bcast.sendTransform(ouster_ros::transform_to_tf_msg( - info.imu_to_sensor_transform, sensor_frame, imu_frame, msg_ts)); }; static inline rclcpp::Time to_ros_time(uint64_t ts) { @@ -341,7 +344,7 @@ class OusterCloud : public OusterProcessingNodeBase { std::string imu_frame; std::string lidar_frame; - tf2_ros::TransformBroadcaster tf_bcast; + tf2_ros::StaticTransformBroadcaster tf_bcast; bool use_ros_time; From df7e292a1058fc0c5feb81162c8412e7d51f153d Mon Sep 17 00:00:00 2001 From: Adam Aposhian Date: Mon, 1 May 2023 10:08:01 -0600 Subject: [PATCH 3/3] Revert "use separate params for tf frames" This reverts commit 4361969cbd03e7667531d11fd2a508aafd53117d. --- ouster-ros/config/parameters.yaml | 4 +--- ouster-ros/launch/record.composite.launch.xml | 8 ++------ ouster-ros/launch/replay.composite.launch.xml | 8 ++------ ouster-ros/launch/sensor.composite.launch.xml | 8 ++------ ouster-ros/launch/sensor.independent.launch.xml | 8 ++------ ouster-ros/launch/sensor_mtp.launch.xml | 8 ++------ ouster-ros/src/os_cloud_node.cpp | 13 +++++++------ 7 files changed, 18 insertions(+), 39 deletions(-) diff --git a/ouster-ros/config/parameters.yaml b/ouster-ros/config/parameters.yaml index 9c0b7590..44189e15 100644 --- a/ouster-ros/config/parameters.yaml +++ b/ouster-ros/config/parameters.yaml @@ -12,7 +12,5 @@ ouster/os_sensor: imu_port: 0 ouster/os_cloud: ros__parameters: - sensor_frame: '' # Frame of physical sensor - lidar_frame: '' # Frame of lidar scans - imu_frame: '' # Frame of IMU data + tf_prefix: '' timestamp_mode: '' diff --git a/ouster-ros/launch/record.composite.launch.xml b/ouster-ros/launch/record.composite.launch.xml index aab8335b..d219d093 100644 --- a/ouster-ros/launch/record.composite.launch.xml +++ b/ouster-ros/launch/record.composite.launch.xml @@ -41,9 +41,7 @@ description="whether to run a rviz"/> - - - + @@ -61,9 +59,7 @@ - - - + diff --git a/ouster-ros/launch/replay.composite.launch.xml b/ouster-ros/launch/replay.composite.launch.xml index 6732a671..2941ba30 100644 --- a/ouster-ros/launch/replay.composite.launch.xml +++ b/ouster-ros/launch/replay.composite.launch.xml @@ -18,9 +18,7 @@ description="whether to run a rviz"/> - - - + @@ -31,9 +29,7 @@ - - - + diff --git a/ouster-ros/launch/sensor.composite.launch.xml b/ouster-ros/launch/sensor.composite.launch.xml index d50b4dfc..cd2965c1 100644 --- a/ouster-ros/launch/sensor.composite.launch.xml +++ b/ouster-ros/launch/sensor.composite.launch.xml @@ -39,9 +39,7 @@ description="whether to run a rviz"/> - - - + @@ -59,9 +57,7 @@ - - - + diff --git a/ouster-ros/launch/sensor.independent.launch.xml b/ouster-ros/launch/sensor.independent.launch.xml index 64d39c40..a40c09f7 100644 --- a/ouster-ros/launch/sensor.independent.launch.xml +++ b/ouster-ros/launch/sensor.independent.launch.xml @@ -39,9 +39,7 @@ description="whether to run a rviz"/> - - - + @@ -58,9 +56,7 @@ - - - + diff --git a/ouster-ros/launch/sensor_mtp.launch.xml b/ouster-ros/launch/sensor_mtp.launch.xml index f604a9d9..7fe115f7 100644 --- a/ouster-ros/launch/sensor_mtp.launch.xml +++ b/ouster-ros/launch/sensor_mtp.launch.xml @@ -47,9 +47,7 @@ description="whether to run a rviz"/> - - - + @@ -67,9 +65,7 @@ - - - + diff --git a/ouster-ros/src/os_cloud_node.cpp b/ouster-ros/src/os_cloud_node.cpp index c3261a06..061fe41c 100644 --- a/ouster-ros/src/os_cloud_node.cpp +++ b/ouster-ros/src/os_cloud_node.cpp @@ -91,16 +91,17 @@ class OusterCloud : public OusterProcessingNodeBase { } void declare_parameters() { - declare_parameter("lidar_frame"); - declare_parameter("sensor_frame"); - declare_parameter("imu_frame"); + declare_parameter("tf_prefix"); declare_parameter("timestamp_mode"); } void parse_parameters() { - sensor_frame = get_parameter("sensor_frame").as_string(); - imu_frame = get_parameter("imu_frame").as_string(); - lidar_frame = get_parameter("lidar_frame").as_string(); + auto tf_prefix = get_parameter("tf_prefix").as_string(); + if (is_arg_set(tf_prefix) && tf_prefix.back() != '/') + tf_prefix.append("/"); + sensor_frame = tf_prefix + "os_sensor"; + imu_frame = tf_prefix + "os_imu"; + lidar_frame = tf_prefix + "os_lidar"; auto timestamp_mode_arg = get_parameter("timestamp_mode").as_string(); use_ros_time = timestamp_mode_arg == "TIME_FROM_ROS_TIME"; }