From cee5af8453fc8ef0f3cdab1be30e1e95f7572572 Mon Sep 17 00:00:00 2001 From: Ussama Naal Date: Fri, 2 Aug 2024 09:24:37 -0700 Subject: [PATCH] Turn off pcap by default and update change log and readme --- CHANGELOG.rst | 2 ++ CMakeLists.txt | 12 +++++++++--- README.md | 17 ++++++++++++++++- package.xml | 2 +- 4 files changed, 28 insertions(+), 5 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 16f70070..fe3b6b38 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -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 diff --git a/CMakeLists.txt b/CMakeLists.txt index 2fceca39..284d5486 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,7 +64,7 @@ set(_SAVE_BUILD_SHARED_LIBS ${BUILD_SHARED_LIBS}) set(BUILD_SHARED_LIBS OFF) option(BUILD_VIZ "Enabled for Python build" OFF) -option(BUILD_PCAP "Enabled for Python build" ON) +option(BUILD_PCAP "Enabled for Python build" OFF) find_package(OusterSDK REQUIRED) set(BUILD_SHARED_LIBS ${_SAVE_BUILD_SHARED_LIBS}) @@ -75,9 +75,15 @@ 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 ouster_pcap -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 ==== diff --git a/README.md b/README.md index 97789ce5..07018417 100644 --- a/README.md +++ b/README.md @@ -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) @@ -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: @@ -131,7 +135,7 @@ over `sensor.launch`. `sensor.launch` is mainly provided for backward compatibil ```bash roslaunch ouster_ros record.launch \ sensor_hostname:= \ - bag_file:= + bag_file:= \ metadata:= # optional ``` #### Replay Mode @@ -145,6 +149,17 @@ roslaunch ouster_ros replay.launch \ metadata:= # 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:= \ + metadata:= # 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 diff --git a/package.xml b/package.xml index 0785f997..d8e66bff 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ ouster_ros - 0.12.3 + 0.12.4 Ouster ROS driver ouster developers BSD