Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS[NOETIC] Add a pcap source reader nodelet #344

Merged
merged 9 commits into from
Aug 15, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ Changelog
* [BUGFIX]: Implement lock free ring buffer with throttling to avoid generating partial frames
* add support for FUSA udp profile ``FUSA_RNG15_RFL8_NIR8_DUAL``.
* [BREAKING] Set xyz values of individual points in the PointCloud to NaNs when range is zero.
* Added support to replay pcap format direclty from ouster-ros. The feature needs to be enabled
explicitly by turning on the ``BUILD_PCAP`` cmake option and having ``libpcap-dev`` installed.


ouster_ros v0.10.0
Expand Down
18 changes: 14 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,10 @@ add_service_files(FILES GetConfig.srv SetConfig.srv GetMetadata.srv)
generate_messages(DEPENDENCIES std_msgs sensor_msgs geometry_msgs)

set(_ouster_ros_INCLUDE_DIRS
"include;ouster-sdk/ouster_client/include;ouster-sdk/ouster_client/include/optional-lite")
"include;"
"ouster-sdk/ouster_client/include;"
"ouster-sdk/ouster_client/include/optional-lite;"
"ouster-sdk/ouster_pcap/include")

catkin_package(
INCLUDE_DIRS
Expand Down Expand Up @@ -72,16 +75,23 @@ include_directories(${_ouster_ros_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})
# use only MPL-licensed parts of eigen
add_definitions(-DEIGEN_MPL2_ONLY)

set(OUSTER_TARGET_LINKS ouster_client)
if (BUILD_PCAP)
list(APPEND OUSTER_TARGET_LINKS ouster_pcap)
endif()

add_library(ouster_ros src/os_ros.cpp)
target_link_libraries(ouster_ros PUBLIC ${catkin_LIBRARIES} ouster_build pcl_common PRIVATE
-Wl,--whole-archive ouster_client -Wl,--no-whole-archive)
target_link_libraries(ouster_ros
PUBLIC ${catkin_LIBRARIES} ouster_build pcl_common
PRIVATE -Wl,--whole-archive ${OUSTER_TARGET_LINKS} -Wl,--no-whole-archive)
add_dependencies(ouster_ros ${PROJECT_NAME}_gencpp)

# ==== Executables ====
add_library(${PROJECT_NAME}_nodelets
src/os_sensor_nodelet_base.cpp
src/os_sensor_nodelet.cpp
src/os_replay_nodelet.cpp
src/os_pcap_nodelet.cpp
src/os_cloud_nodelet.cpp
src/os_image_nodelet.cpp
src/os_driver_nodelet.cpp)
Expand All @@ -100,7 +110,7 @@ if(CATKIN_ENABLE_TESTING)
tests/point_cloud_compose_test.cpp
)
target_link_libraries(${PROJECT_NAME}_test ${catkin_LIBRARIES}
ouster_build pcl_common -Wl,--whole-archive ouster_client -Wl,--no-whole-archive)
ouster_build pcl_common -Wl,--whole-archive ${OUSTER_TARGET_LINKS} -Wl,--no-whole-archive)
endif()

# ==== Install ====
Expand Down
17 changes: 16 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
- [Sensor Mode](#sensor-mode)
- [Recording Mode](#recording-mode)
- [Replay Mode](#replay-mode)
- [PCAP Replay Mode](#pcap-replay-mode)
- [Multicast Mode (experimental)](#multicast-mode-experimental)
- [Launch Files Arguments](#launch-files-arguments)
- [Invoking Services](#invoking-services)
Expand Down Expand Up @@ -80,6 +81,9 @@ sudo apt install -y \
> **Note**
> You may choose a different ssl backend for the curl library such as `libcurl4-gnutls-dev` or `libcurl4-nss-dev`

> **Note**
> To use the PCAP replay mode you need to have `libpcap-dev` installed

## Getting Started
To build the driver using ROS you need to clone the project into the `src` folder of a catkin workspace
as shown below:
Expand Down Expand Up @@ -131,7 +135,7 @@ over `sensor.launch`. `sensor.launch` is mainly provided for backward compatibil
```bash
roslaunch ouster_ros record.launch \
sensor_hostname:=<sensor host name> \
bag_file:=<optional bag file name>
bag_file:=<optional bag file name> \
metadata:=<json file name> # optional
```
#### Replay Mode
Expand All @@ -145,6 +149,17 @@ roslaunch ouster_ros replay.launch \
metadata:=<json file name> # optional if bag file has /metadata topic
```

##### PCAP Replay Mode
> Note
> To use this feature you need to compile the driver with `BUILD_PCAP` option enabled

```bash
roslaunch ouster_ros replay_pcap.launch \
pcap_file:=<path to ouster pcap file> \
metadata:=<json file name> # required
```


#### Multicast Mode (experimental)
The multicast launch mode supports configuring the sensor to broadcast lidar packets from the same
sensor (live) to multiple active clients. You initiate this mode by using `sensor_mtp.launch` file
Expand Down
11 changes: 8 additions & 3 deletions launch/replay.launch
Original file line number Diff line number Diff line change
@@ -1,10 +1,15 @@
<launch>

<param name="use_sim_time" value="true"/>

<arg name="ouster_ns" default="ouster" doc="Override the default namespace of all ouster nodes"/>
<arg name="metadata" default ="" doc="path to read metadata file when replaying sensor data"/>
<arg name="bag_file" default="" doc="file name to use for the recorded bag file"/>
<arg name="timestamp_mode" default=" " doc="A parameter that allows you to override the timestamp measurements;
<arg name="metadata" default="" doc="path to read metadata file when replaying sensor data"/>
<arg name="bag_file" doc="file name to use for the recorded bag file"/>
<arg name="timestamp_mode" default="TIME_FROM_INTERNAL_OSC" doc="A parameter that allows you to override the 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"
Expand Down
92 changes: 92 additions & 0 deletions launch/replay_pcap.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
<launch>

<!-- NOTE: pcap replay node does not implement clock-->
<param name="use_sim_time" value="false"/>

<arg name="ouster_ns" default="ouster" doc="Override the default namespace of all ouster nodes"/>
<arg name="metadata" doc="path to read metadata file when replaying sensor data"/>
<arg name="pcap_file" doc="file name to use for the recorded pcap file"/>
<arg name="timestamp_mode" default="TIME_FROM_INTERNAL_OSC" doc="A parameter that allows you to override the 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"
Samahu marked this conversation as resolved.
Show resolved Hide resolved
doc="UTC/TAI offset in seconds to apply when using TIME_FROM_PTP_1588"/>
<arg name="viz" default="true" doc="whether to run a rviz"/>
<arg name="rviz_config" default="$(find ouster_ros)/config/viz.rviz" doc="optional rviz config file"/>

<arg name="tf_prefix" default=" " doc="namespace for tf transforms"/>
<arg name="sensor_frame" default="os_sensor"
doc="sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" default="os_lidar"
doc="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
doc="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=" "
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"/>
<arg name="dynamic_transforms_broadcast_rate" default="1.0"
doc="set the rate (Hz) of broadcast when using dynamic broadcast; minimum value is 1 Hz"/>

<arg name="proc_mask" default="IMG|PCL|IMU|SCAN" doc="
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" doc="
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" doc="point type for the generated point cloud;
available options: {
original,
native,
xyz,
xyzi,
xyzir
}"/>

<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
output="screen" required="true" args="manager"/>
</group>

<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet"
name="os_node" output="screen" required="true"
launch-prefix="bash -c 'sleep 3; $0 $@' "
args="load ouster_ros/OusterPcap os_nodelet_mgr">
<param name="~/metadata" value="$(arg metadata)"/>
<param name="~/pcap_file" value="$(arg pcap_file)"/>
</node>
</group>

<include file="$(find ouster_ros)/launch/common.launch">
<arg name="ouster_ns" value="$(arg ouster_ns)"/>
<arg name="viz" value="$(arg viz)"/>
<arg name="rviz_config" value="$(arg rviz_config)"/>
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
<arg name="sensor_frame" value="$(arg sensor_frame)"/>
<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="timestamp_mode" value="$(arg timestamp_mode)"/>
<arg name="ptp_utc_tai_offset" value="$(arg ptp_utc_tai_offset)"/>
<arg name="dynamic_transforms_broadcast"
value="$(arg dynamic_transforms_broadcast)"/>
<arg name="dynamic_transforms_broadcast_rate"
value="$(arg dynamic_transforms_broadcast_rate)"/>
<arg name="proc_mask" value="$(arg proc_mask)"/>
<arg name="scan_ring" value="$(arg scan_ring)"/>
<arg name="point_type" value="$(arg point_type)"/>
</include>


</launch>
5 changes: 5 additions & 0 deletions ouster_ros_nodelets.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,11 @@
A nodelet that can load up existing Ouster recordings and replay them.
</description>
</class>
<class name="ouster_ros/OusterPcap" type="ouster_ros::OusterPcap" base_class_type="nodelet::Nodelet">
<description>
A nodelet that can directly load ouster sensor data from a pcap file.
</description>
</class>
<class name="ouster_ros/OusterCloud" type="ouster_ros::OusterCloud" base_class_type="nodelet::Nodelet">
<description>
A nodelet that process incoming Ouster lidar packets and publishes a corresponding point cloud.
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.12.3</version>
<version>0.12.4</version>
<description>Ouster ROS driver</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license file="LICENSE">BSD</license>
Expand Down
Loading
Loading