Skip to content

Commit

Permalink
Initialize point_cloud_frame with an empty string + and expose point_…
Browse files Browse the repository at this point in the history
…cloud_frame through launch xml files +

Remove unused/duplicate param definitions +
Update descriptions
  • Loading branch information
Samahu committed Jul 10, 2023
1 parent 6c9b3f5 commit 0749c54
Show file tree
Hide file tree
Showing 8 changed files with 88 additions and 53 deletions.
4 changes: 2 additions & 2 deletions ouster-ros/config/driver_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ ouster/os_driver:
# to select which beam of the LidarScan to use when producing the LaserScan
# message. Choose a value the range [0, sensor_beams_count).
scan_ring: 0
# use_system_default_qos[optional]: if False, data are published with sensor
# use_system_default_qos[optional]: if false, data are published with sensor
# data QoS. This is preferrable for production but default QoS is needed for
# rosbag. See: https://github.com/ros2/rosbag2/issues/125
use_system_default_qos: False
use_system_default_qos: false
29 changes: 20 additions & 9 deletions ouster-ros/launch/record.composite.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -42,16 +42,28 @@
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor" description="value can not be empty"/>
<arg name="lidar_frame" default="os_lidar" description="value can not be empty"/>
<arg name="imu_frame" default="os_imu" description="value can not be empty"/>
<arg name="sensor_frame" default="os_sensor"
description="sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" default="os_lidar"
description="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
description="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
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."/>

<arg name="use_system_default_qos" default="true" description="Use the default system QoS settings"/>
<arg name="use_system_default_qos" default="true"
description="Use the default system QoS settings"/>

<arg name="proc_mask" default="IMG|PCL|IMU|SCAN" description="
The IMG flag here is not supported and does not affect anything,
to disable image topics you would need to omit the os_image node
from the launch file"/>

<arg name="scan_ring" default="0" description="
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"
/>
and choose a value the range [0, sensor_beams_count)"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
Expand All @@ -73,8 +85,10 @@
<param name="sensor_frame" value="$(var sensor_frame)"/>
<param name="lidar_frame" value="$(var lidar_frame)"/>
<param name="imu_frame" value="$(var imu_frame)"/>
<param name="point_cloud_frame" value="$(var point_cloud_frame)"/>
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="proc_mask" value="$(var proc_mask)"/>
<param name="scan_ring" value="$(var scan_ring)"/>
</composable_node>
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterImage" name="os_image">
Expand All @@ -93,9 +107,6 @@
<include if="$(var viz)" file="$(find-pkg-share ouster_ros)/launch/rviz.launch.xml">
<arg name="ouster_ns" value="$(var ouster_ns)"/>
<arg name="rviz_config" value="$(var rviz_config)"/>
<arg name="sensor_frame" value="$(var sensor_frame)"/>
<arg name="lidar_frame" value="$(var lidar_frame)"/>
<arg name="imu_frame" value="$(var imu_frame)"/>
</include>

<let name="_use_bag_file_name" value="$(eval '\'$(var bag_file)\' != \'b\'')"/>
Expand Down
31 changes: 21 additions & 10 deletions ouster-ros/launch/replay.composite.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,19 +19,31 @@
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor" description="value can not be empty"/>
<arg name="lidar_frame" default="os_lidar" description="value can not be empty"/>
<arg name="imu_frame" default="os_imu" description="value can not be empty"/>
<arg name="sensor_frame" default="os_sensor"
description="sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" default="os_lidar"
description="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
description="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
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."/>

<let name="_use_metadata_file" value="$(eval '\'$(var metadata)\' != \'\'')"/>

<arg name="use_system_default_qos" default="true" description="Use the default system QoS settings"/>
<arg name="use_system_default_qos" default="true"
description="Use the default system QoS settings"/>

<arg name="proc_mask" default="IMG|PCL|IMU|SCAN" description="
The IMG flag here is not supported and does not affect anything,
to disable image topics you would need to omit the os_image node
from the launch file"/>


<arg name="scan_ring" default="0" description="
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"
/>

and choose a value the range [0, sensor_beams_count)"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
Expand All @@ -44,8 +56,10 @@
<param name="sensor_frame" value="$(var sensor_frame)"/>
<param name="lidar_frame" value="$(var lidar_frame)"/>
<param name="imu_frame" value="$(var imu_frame)"/>
<param name="point_cloud_frame" value="$(var point_cloud_frame)"/>
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="proc_mask" value="$(var proc_mask)"/>
<param name="scan_ring" value="$(var scan_ring)"/>
</composable_node>
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterImage" name="os_image">
Expand All @@ -66,9 +80,6 @@
<include if="$(var viz)" file="$(find-pkg-share ouster_ros)/launch/rviz.launch.xml">
<arg name="ouster_ns" value="$(var ouster_ns)"/>
<arg name="rviz_config" value="$(var rviz_config)"/>
<arg name="sensor_frame" value="$(var sensor_frame)"/>
<arg name="lidar_frame" value="$(var lidar_frame)"/>
<arg name="imu_frame" value="$(var imu_frame)"/>
</include>

<let name="_use_bag_file_name" value="$(eval '\'$(var bag_file)\' != \'b\'')"/>
Expand Down
4 changes: 0 additions & 4 deletions ouster-ros/launch/rviz.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,6 @@
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor" description="value can not be empty"/>
<arg name="lidar_frame" default="os_lidar" description="value can not be empty"/>
<arg name="imu_frame" default="os_imu" description="value can not be empty"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen"
Expand Down
28 changes: 16 additions & 12 deletions ouster-ros/launch/sensor.composite.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -40,19 +40,26 @@
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor" description="value can not be empty"/>
<arg name="lidar_frame" default="os_lidar" description="value can not be empty"/>
<arg name="imu_frame" default="os_imu" description="value can not be empty"/>
<arg name="sensor_frame" default="os_sensor"
description="sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" default="os_lidar"
description="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
description="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
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."/>

<arg name="use_system_default_qos" default="false" description="Use the default system QoS settings"/>
<arg name="use_system_default_qos" default="false"
description="Use the default system QoS settings"/>

<arg name="proc_mask" default="IMG|PCL|IMU|SCAN" description="
use any combination of the 4 flags to enable or disable specific processors"
/>
use any combination of the 4 flags to enable or disable specific processors"/>

<arg name="scan_ring" default="0" description="
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"
/>
and choose a value the range [0, sensor_beams_count)"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
Expand All @@ -65,11 +72,11 @@
<param name="imu_port" value="$(var imu_port)"/>
<param name="udp_profile_lidar" value="$(var udp_profile_lidar)"/>
<param name="lidar_mode" value="$(var lidar_mode)"/>
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="metadata" value="$(var metadata)"/>
<param name="sensor_frame" value="$(var sensor_frame)"/>
<param name="lidar_frame" value="$(var lidar_frame)"/>
<param name="imu_frame" value="$(var imu_frame)"/>
<param name="point_cloud_frame" value="$(var point_cloud_frame)"/>
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="proc_mask" value="$(var proc_mask)"/>
Expand All @@ -87,9 +94,6 @@
<include if="$(var viz)" file="$(find-pkg-share ouster_ros)/launch/rviz.launch.xml">
<arg name="ouster_ns" value="$(var ouster_ns)"/>
<arg name="rviz_config" value="$(var rviz_config)"/>
<arg name="sensor_frame" value="$(var sensor_frame)"/>
<arg name="lidar_frame" value="$(var lidar_frame)"/>
<arg name="imu_frame" value="$(var imu_frame)"/>
</include>

</launch>
27 changes: 16 additions & 11 deletions ouster-ros/launch/sensor.independent.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -40,20 +40,28 @@
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor" description="value can not be empty"/>
<arg name="lidar_frame" default="os_lidar" description="value can not be empty"/>
<arg name="imu_frame" default="os_imu" description="value can not be empty"/>
<arg name="sensor_frame" default="os_sensor"
description="sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" default="os_lidar"
description="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
description="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
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."/>

<arg name="use_system_default_qos" default="false"
description="Use the default system QoS settings"/>

<arg name="use_system_default_qos" default="false" description="Use the default system QoS settings"/>
<arg name="proc_mask" default="IMG|PCL|IMU|SCAN" description="
currently IMG is not supported and does not affect anything,
The IMG flag here is not supported and does not affect anything,
to disable image topics you would need to omit the os_image node
from the launch file"/>

<arg name="scan_ring" default="0" description="
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"
/>
and choose a value the range [0, sensor_beams_count)"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
Expand All @@ -69,12 +77,12 @@
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="metadata" value="$(var metadata)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="proc_mask" value="$(var proc_mask)"/>
</node>
<node pkg="ouster_ros" exec="os_cloud" name="os_cloud" output="screen">
<param name="sensor_frame" value="$(var sensor_frame)"/>
<param name="lidar_frame" value="$(var lidar_frame)"/>
<param name="imu_frame" value="$(var imu_frame)"/>
<param name="point_cloud_frame" value="$(var point_cloud_frame)"/>
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="proc_mask" value="$(var proc_mask)"/>
Expand All @@ -95,9 +103,6 @@
<include if="$(var viz)" file="$(find-pkg-share ouster_ros)/launch/rviz.launch.xml">
<arg name="ouster_ns" value="$(var ouster_ns)"/>
<arg name="rviz_config" value="$(var rviz_config)"/>
<arg name="sensor_frame" value="$(var sensor_frame)"/>
<arg name="lidar_frame" value="$(var lidar_frame)"/>
<arg name="imu_frame" value="$(var imu_frame)"/>
</include>

</launch>
16 changes: 12 additions & 4 deletions ouster-ros/launch/sensor_mtp.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,20 @@
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor" description="value can not be empty"/>
<arg name="lidar_frame" default="os_lidar" description="value can not be empty"/>
<arg name="imu_frame" default="os_imu" description="value can not be empty"/>
<arg name="sensor_frame" default="os_sensor"
description="sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" default="os_lidar"
description="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
description="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
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."/>

<arg name="use_system_default_qos" default="false"
description="Use the default system QoS settings"/>

<arg name="proc_mask" default="IMG|PCL|IMU|SCAN"
description="Use any combination of the 4 flags to enable or disable specific processors"/>

Expand All @@ -72,11 +80,11 @@
<param name="imu_port" value="$(var imu_port)"/>
<param name="udp_profile_lidar" value="$(var udp_profile_lidar)"/>
<param name="lidar_mode" value="$(var lidar_mode)"/>
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="metadata" value="$(var metadata)"/>
<param name="sensor_frame" value="$(var sensor_frame)"/>
<param name="lidar_frame" value="$(var lidar_frame)"/>
<param name="imu_frame" value="$(var imu_frame)"/>
<param name="point_cloud_frame" value="$(var point_cloud_frame)"/>
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="proc_mask" value="$(var proc_mask)"/>
Expand Down
2 changes: 1 addition & 1 deletion ouster-ros/src/os_static_transforms_broadcaster.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ class OusterStaticTransformsBroadcaster {
node->declare_parameter("sensor_frame", "os_sensor");
node->declare_parameter("lidar_frame", "os_lidar");
node->declare_parameter("imu_frame", "os_imu");
node->declare_parameter("point_cloud_frame", "os_lidar");
node->declare_parameter("point_cloud_frame", "");
}

void parse_parameters() {
Expand Down

0 comments on commit 0749c54

Please sign in to comment.