-
Notifications
You must be signed in to change notification settings - Fork 153
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
ROS2[HUMBLE/IRON] add pcap reader (#355)
* Port the pcap replay to ros2-foxy * Add time update
- Loading branch information
Showing
7 changed files
with
500 additions
and
13 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,98 @@ | ||
<launch> | ||
|
||
<!-- NOTE: pcap replay node does not implement clock--> | ||
<set_parameter name="use_sim_time" value="false" /> | ||
|
||
<arg name="ouster_ns" default="ouster" | ||
description="Override the default namespace of all ouster nodes"/> | ||
<arg name="timestamp_mode" default="TIME_FROM_INTERNAL_OSC" | ||
description="method used to timestamp measurements; possible values: { | ||
TIME_FROM_INTERNAL_OSC, | ||
TIME_FROM_SYNC_PULSE_IN, | ||
TIME_FROM_PTP_1588, | ||
TIME_FROM_ROS_TIME | ||
}"/> | ||
<arg name="ptp_utc_tai_offset" default="-37.0" | ||
description="UTC/TAI offset in seconds to apply when using TIME_FROM_PTP_1588"/> | ||
<arg name="metadata" description="path to write metadata file when receiving sensor data"/> | ||
<arg name="pcap_file" description="file name to use for the recorded bag file"/> | ||
<arg name="viz" default="true" | ||
description="whether to run a rviz"/> | ||
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz-reliable.rviz" | ||
description="optional rviz config file"/> | ||
|
||
<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="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)"/> | ||
|
||
<arg name="point_type" default="original" description="point type for the generated point cloud; | ||
available options: { | ||
original, | ||
native, | ||
xyz, | ||
xyzi, | ||
xyzir | ||
}"/> | ||
|
||
<group> | ||
<push-ros-namespace namespace="$(var ouster_ns)"/> | ||
<node if="$(var _use_metadata_file)" pkg="ouster_ros" exec="os_pcap" name="os_pcap" output="screen"> | ||
<param name="metadata" value="$(var metadata)"/> | ||
<param name="pcap_file" value="$(var pcap_file)"/> | ||
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/> | ||
</node> | ||
<node_container pkg="rclcpp_components" exec="component_container_mt" name="os_container" output="screen" namespace=""> | ||
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterCloud" name="os_cloud"> | ||
<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="ptp_utc_tai_offset" value="$(var ptp_utc_tai_offset)"/> | ||
<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)"/> | ||
<param name="point_type" value="$(var point_type)"/> | ||
</composable_node> | ||
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterImage" name="os_image"> | ||
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/> | ||
</composable_node> | ||
</node_container> | ||
</group> | ||
|
||
<!-- HACK: configure and activate the replay node via a process execute since state | ||
transition is currently not availabe through launch.xml format --> | ||
<executable if="$(var _use_metadata_file)" | ||
cmd="$(find-exec ros2) lifecycle set /$(var ouster_ns)/os_pcap configure" | ||
launch-prefix="bash -c 'sleep 0; $0 $@'" output="screen"/> | ||
<executable if="$(var _use_metadata_file)" | ||
cmd="$(find-exec ros2) lifecycle set /$(var ouster_ns)/os_pcap activate" | ||
launch-prefix="bash -c 'sleep 1; $0 $@'" output="screen"/> | ||
|
||
<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)"/> | ||
</include> | ||
|
||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -2,7 +2,7 @@ | |
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> | ||
<package format="3"> | ||
<name>ouster_ros</name> | ||
<version>0.12.4</version> | ||
<version>0.12.5</version> | ||
<description>Ouster ROS2 driver</description> | ||
<maintainer email="[email protected]">ouster developers</maintainer> | ||
<license file="LICENSE">BSD</license> | ||
|
Oops, something went wrong.