Skip to content

Commit

Permalink
ROS2 foxy compatibility mode (#149)
Browse files Browse the repository at this point in the history
* Squashed commit of the following:
- remove deprecated methods + naming nits
-  Added notes to size(), empty(), full()
-  Expose scan_ring param and update relevant params description
- Added ImageProcessor to support IMG flag
- Define new argument scan_ring
- Re-formatting CHANGELOG a bit
- Add missing parameter declaration
- Apply && to accepted method of ThreadSafeRingBuffer +  nits and code formatting
- Update CHANGELOG.rst and package version
- Update minimal readme file and utilize os_driver by default
- Add proc_mask to xml file
- Remove experminal marker from set_config and reset ros services
- Expose use_system_default_qos parameter to xml launch file and use proper defaults
- Rename the file os_sensor_cloud_image_params to os_sensor_cloud_image_params.yaml and update corresponding launch files
- More detailed explanation about the IMG node
- Add minor note
- Add the ability to override current qos settings
- Reduce sync operations + restore sensor reset/reactivation
- Add support for the selecting IMU
- Create topics/subs when their respective flags enabled
- Parse proc_mask and hook to launch files and config
- Restor os_cloud_node ability to process point clouds
- Refactor a bit and add the ability to process and publish point clouds and laser scans
- Incorporate LaserScan message composition
- Fix build issue
- Formatting imu and lidar packet handlers
- Factor out tf transforms broadcast
- Provide support for parsing the community driver params file with approprite launch file
- Formatting os_sensor and os_driver
- Keep transforms in Lidar Frame by default with option to switch
- Add an option to select the point_cloud frame
- Quick hook up of the ThreadSafeRingBuffer for os_sensor and os_driver
- Add one more case to the unit test of ThreadSafeRingBuffer
- Adding unit tests for the ThreadSafeRingBuffer
- Move down pragma once in the handlers
- Added os_driver which combines os_sensor and os_cloud
- Added required launch files
- Better abstraction of classes
- Simplified threading logic
- Added thread safe implemention of ring buffer (not hooked yet)
- Factoring out Imu and Lidar packets handling
* Update CHANGELOG + Fix load_metadata_from_file
* Correct params file used in driver.launch.py + add comments
* Fix pub activation and re-enable sensor re-configuration
* Fix trying to publish on an inactive topic
* Update REAMDE.md to mention the Compatibilty mode
* Use angle-bracket include for laser_scan.hpp
* Fix the 2nd point cloud replacing the first
* Properly check for the write_text_to_file
  • Loading branch information
Samahu committed Jun 28, 2023
1 parent 4774e8b commit 09409f0
Show file tree
Hide file tree
Showing 38 changed files with 3,291 additions and 1,186 deletions.
14 changes: 14 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,20 @@ ouster_ros(2)
* bugfix: fixed an issue that prevents running multiple instances of the sensor and cloud components
in the same process.
* switch to using static transform publisher for the ros2 driver.
* implemented a new node named ``os_driver`` which combines the functionality of ``os_sensor``,
``os_cloud`` and ``os_image`` into a single node.
* added support to parse the same parameters provided by the ``ros2_ouster_driver``, the parameters
are ``lidar_ip``, ``computer_ip``, ``proc_mask`` and ``use_system_default_qos``; the parameters
are fully functional and similar to what the ``ros2_ouster_driver`` provides.
* for convenience introduced a new launch file ``driver_launch.py`` that is compatible with the
``ros2_ouster_driver`` in terms of parameters it accepts and the name of published topics.
* introduced a new parameter ``point_cloud_frame`` to allow users to select which frame to use when
publishing the point cloud (choose between ``sensor`` and ``lidar``).
* breaking: ``lidar`` frame is the default frame used when publishing point clouds.
* added the ability to choose between ``SensorDataQoS`` or ``SystemDefaultQoS`` across all published
topics with ``SensorDataQoS`` selected by default for live sensor mode and ``SystemDefaultQoS``
enabled for record and replay modes.
* introduced a new topic ``/ouster/scan`` which publishes ``sensor_msgs::msg::LaserScan`` messages

ouster_client
-------------
Expand Down
4 changes: 4 additions & 0 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,14 @@ RUN set -xe \
FROM build-env

SHELL ["/bin/bash", "-c"]

RUN source /opt/ros/$ROS_DISTRO/setup.bash && colcon build \
--symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release \
-DCMAKE_CXX_FLAGS="-Wno-deprecated-declarations"

RUN source /opt/ros/$ROS_DISTRO/setup.bash && colcon test \
--ctest-args tests ouster_ros --rerun-failed --output-on-failure

# Entrypoint for running Ouster ros:
#
# Usage: docker run --rm -it ouster-ros [sensor.launch parameters ..]
Expand Down
67 changes: 45 additions & 22 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,31 +1,36 @@
# Official ROS driver for Ouster sensors

[ROS1 (melodic/noetic)](https://github.com/ouster-lidar/ouster-ros/tree/master) |
[ROS2 (rolling/humble)](https://github.com/ouster-lidar/ouster-ros/tree/ros2) |
[ROS2 (rolling/humble/iron)](https://github.com/ouster-lidar/ouster-ros/tree/ros2) |
[ROS2 (foxy)](https://github.com/ouster-lidar/ouster-ros/tree/ros2-foxy)

<p style="float: right;"><img width="20%" src="docs/images/logo.png" /></p>

| ROS Version | Build Status (Linux) |
|:-----------:|:------:|
| ROS1 (melodic/noetic) | [![melodic/noetic](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml/badge.svg?branch=master)](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml)
| ROS2 (rolling/humble) | [![rolling/humble](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml/badge.svg?branch=ros2)](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml)
| ROS2 (rolling/humble/iron) | [![rolling/humble/iron](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml/badge.svg?branch=ros2)](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml)
| ROS2 (foxy) | [![foxy](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml/badge.svg?branch=ros2-foxy)](https://github.com/ouster-lidar/ouster-ros/actions/workflows/docker-image.yml)

- [Overview](#overview)
- [Requirements](#requirements)
- [Getting Started](#getting-started)
- [Usage](#usage)
- [Launching Nodes](#launching-nodes)
- [Sensor Mode](#sensor-mode)
- [Recording Mode](#recording-mode)
- [Replay Mode](#replay-mode)
- [Multicast Mode (experimental)](#multicast-mode-experimental)
- [Invoking Services](#invoking-services)
- [GetMetadata](#getmetadata)
- [GetConfig](#getconfig)
- [SetConfig (experimental)](#setconfig-experimental)
- [License](#license)
- [Official ROS driver for Ouster sensors](#official-ros-driver-for-ouster-sensors)
- [Overview](#overview)
- [Requirements](#requirements)
- [Linux](#linux)
- [Windows](#windows)
- [Mac](#mac)
- [Getting Started](#getting-started)
- [Usage](#usage)
- [Launching Nodes](#launching-nodes)
- [Sensor Mode](#sensor-mode)
- [Recording Mode](#recording-mode)
- [Replay Mode](#replay-mode)
- [Multicast Mode (experimental)](#multicast-mode-experimental)
- [Invoking Services](#invoking-services)
- [GetMetadata](#getmetadata)
- [GetConfig](#getconfig)
- [SetConfig](#setconfig)
- [Reset](#reset)
- [License](#license)


## Overview
Expand All @@ -38,8 +43,8 @@ dual return and it was configured to use this capability, then another topic wil
name `/ouster/points2` which corresponds to the second point cloud.

## Requirements
This driver only supports **Foxy** ROS 2 distro. Please refer to ROS 2 online documentation on how to
setup ros on your machine before proceeding with the remainder of this guide.
This branch is only intended for use with the **Foxy** ROS 2 distro. Please refer to ROS 2 online documentation on how to
setup ROS on your machine before proceeding with the remainder of this guide.

> **Note**
> If you have _rosdep_ tool installed on your system you can then use the following command to get all
Expand Down Expand Up @@ -119,14 +124,32 @@ source ros2_ws/install/setup.bash
## Usage

### Launching Nodes
The package supports three modes of interaction, you can connect to a _live sensor_, _replay_ a recorded bag or _record_ a new bag file using the corresponding launch files. Recently, we have
added a new mode that supports multicast. The commands are listed below:
The package supports three modes of interaction, you can connect to a _live sensor_, _replay_ a
recorded bag or _record_ a new bag file using the corresponding launch files. Recently, we have
added a new mode that supports multicast. The commands are listed below, for convenience we do
provide both launch file formats (xml and python) but the python format is preferred method:

#### Sensor Mode
To connect to a live sensor you use the following launch file
```bash
ros2 launch ouster_ros sensor.launch.xml \
sensor_hostname:=<sensor host name>
```
The equivalent python file is
```bash
ros2 launch ouster_ros driver.launch.py \
params_files:=<path to params yaml file>
```
If you don't pass a params_file then the file located at `ouster/config/driver_params.yaml` will be used. Note that in
the params you can start with default options for everything except the `sensor_hostname` param which you should adjust
to match the hostname or ip address of the Ouster sensor you are trying to connect to.

**comptability mode**
If you are migrating from https://github.com/ros-drivers/ros2_ouster_drivers to the official ouster drivers
we supply you with a file `driver_launch.py` which provides users with same topic name and accepts the same
parameter file `community_driver_config.yaml`. Please note that this is provided for backward compatibilty
it may not be maintained in the future, so it would be better to update to the new format `driver_params.yaml`
which offers the same options and more.

#### Recording Mode
> Note
Expand Down Expand Up @@ -197,14 +220,14 @@ To get the current config of a live sensor, invoke the command:
ros2 service call /ouster/get_config ouster_srvs/srv/GetConfig
```

#### SetConfig (experimental)
#### SetConfig
To change config via a file while connected to a live sensor, invoke the command:
```bash
ros2 service call /ouster/set_config ouster_srvs/srv/SetConfig \
"{config_file: 'some_config.json'}"
```

#### Reset (experimental)
#### Reset
To reset the new reset service, execute the following commnad:
```bash
ros2 service call /ouster/reset std_srvs/srv/Empty
Expand Down
23 changes: 23 additions & 0 deletions ouster-ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,28 @@ rclcpp_components_register_node(os_image_component
EXECUTABLE os_image
)

# ==== os_sensor_component ====
create_ros2_component(os_driver_component
"src/os_sensor_node_base.cpp;src/os_sensor_node.cpp;src/os_driver_node.cpp"
"std_srvs"
)
rclcpp_components_register_node(os_driver_component
PLUGIN "ouster_ros::OusterDriver"
EXECUTABLE os_driver
)


# ==== Test ====
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
ament_add_gtest(${PROJECT_NAME}_test test/ring_buffer_test.cpp)
target_include_directories(${PROJECT_NAME}_test PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)
endif()


# ==== Install ====
install(
TARGETS
Expand All @@ -164,6 +186,7 @@ install(
os_replay_component
os_cloud_component
os_image_component
os_driver_component
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand Down
Loading

0 comments on commit 09409f0

Please sign in to comment.