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

Use rmw_security_common package #434

Draft
wants to merge 10 commits into
base: ahcorde/rolling/secutiry
Choose a base branch
from
50 changes: 32 additions & 18 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,20 @@ For information about the Design please visit [design](docs/design.md) page.

> Note: See available distro branches, eg. `jazzy`, for supported ROS 2 distributions.

## Setup
## Installation
`rmw_zenoh` can either be installed via binaries (recommended for stable development) or built from source (recommended if latest features are needed). See instructions below.

Build `rmw_zenoh_cpp`
### Binary Installation
Binary packages for supported ROS 2 distributions (see distro branches) are available on respective [Tier-1](https://www.ros.org/reps/rep-2000.html#support-tiers) platforms for the distributions.
First ensure that your system is set up to install ROS 2 binaries by following the instructions [here](https://docs.ros.org/en/rolling/Installation/Ubuntu-Install-Debs.html).

Then install `rmw_zenoh` binaries using the command

```bash
sudo apt update && sudo apt install ros-<DISTRO>-rmw-zenoh-cpp # replace <DISTRO> with the codename for the distribution, eg., rolling
```

### Source Installation

>Note: By default, we vendor and compile `zenoh-cpp` with a subset of `zenoh` features.
The `ZENOHC_CARGO_FLAGS` CMake argument may be overwritten with other features included if required.
Expand All @@ -32,22 +43,13 @@ source /opt/ros/<DISTRO>/setup.bash
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
```

## Test

Make sure to source the built workspace using the commands below prior to running any other commands.
```bash
cd ~/ws_rmw_zenoh
source install/setup.bash
```

### Start the Zenoh router
> Note: Manually launching Zenoh router won't be necessary in the future.
```bash
# terminal 1
ros2 run rmw_zenoh_cpp rmw_zenohd
```

> Note: Without the Zenoh router, nodes will not be able to discover each other since multicast discovery is disabled by default in the node's session config. Instead, nodes will receive discovery information about other peers via the Zenoh router's gossip functionality. See more information on the session configs [below](#configuration).
## Test

### Terminate ROS 2 daemon started with another RMW
```bash
Expand All @@ -57,6 +59,15 @@ Without this step, ROS 2 CLI commands (e.g. `ros2 node list`) may
not work properly since they would query ROS graph information from the ROS 2 daemon that
may have been started with different a RMW.

### Start the Zenoh router
> Note: Manually launching Zenoh router won't be necessary in the future.
```bash
# terminal 1
ros2 run rmw_zenoh_cpp rmw_zenohd
```

> Note: Without the Zenoh router, nodes will not be able to discover each other since multicast discovery is disabled by default in the node's session config. Instead, nodes will receive discovery information about other peers via the Zenoh router's gossip functionality. See more information on the session configs [below](#configuration).

### Run the `talker`
```bash
# terminal 2
Expand Down Expand Up @@ -90,7 +101,7 @@ The behavior is explained in the table below.
| > 0 | Attempts to connect to a Zenoh router in `ZENOH_ROUTER_CHECK_ATTEMPTS` attempts with 1 second wait between checks. |
| unset | Equivalent to `1`: the check is made only once. |

If after the configured number of attempts the Node is still not connected to a `Zenoh router`, the initialisation goes on anyway.
If after the configured number of attempts the Node is still not connected to a `Zenoh router`, the initialisation goes on anyway.
If a `Zenoh router` is started after initialization phase, the Node will automatically connect to it, and autoconnect to other Nodes if gossip scouting is enabled (true with default configuratiuon).

### Session and Router configs
Expand All @@ -111,20 +122,23 @@ export ZENOH_ROUTER_CONFIG_URI=$HOME/MY_ZENOH_ROUTER_CONFIG.json5
```

### Connecting multiple hosts
By default, all discovery traffic is local per host, where the host is the PC running a `Zenoh router`.
To bridge communications across two hosts, the `Zenoh router` configuration for one the hosts must be updated to connect to the other `Zenoh router` at startup.
This is done by specifying an endpoint in host's `Zenoh router` configuration file to as seen below.
In this example, the `Zenoh router` will connect to the `Zenoh router` running on a second host with IP address `192.168.1.1` and port `7447`.
By default, all discovery & communication is restricted within a host, where a host is a machine running a `Zenoh router` along with various ROS 2 nodes with their default [configurations](rmw_zenoh_cpp/config/).
To bridge communications across two or more hosts, the `Zenoh router` configuration for one of the hosts must be updated to connect to the other host's `Zenoh router` at startup.

First, make a copy of the [DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5](rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5) and modify the `connect` block to include the endpoint(s) that the other host's `Zenoh router(s)` is listening on.
For example, if another `Zenoh router` is listening on IP address `192.168.1.1` and port `7447` on its host, modify the config file to connect to this router as shown below:

```json5
/// ... preceding parts of the config file.
{
connect: {
endpoints: ["tcp/192.168.1.1:7447"],
},
}
/// ... following parts of the config file.
```

> Note: To connect multiple hosts, include the endpoints of all `Zenoh routers` in the network.
Then, start the `Zenoh router` after setting the `ZENOH_ROUTER_CONFIG_URI` environment variable to the absolute path of the modified config file.

### Logging

Expand Down
15 changes: 14 additions & 1 deletion rmw_zenoh_cpp/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,20 @@
Changelog for package rmw_zenoh_cpp
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.3.1 (2025-02-04)
------------------
* Bump Zenoh to commit id e4ea6f0 (1.2.0 + few commits) (`#446 <https://github.com/ros2/rmw_zenoh/issues/446>`_)
* Inform users that peers will not discover and communicate with one another until the router is started (`#440 <https://github.com/ros2/rmw_zenoh/issues/440>`_)
* Clear the error after rmw_serialized_message_resize() (`#435 <https://github.com/ros2/rmw_zenoh/issues/435>`_)
* Fix `ZENOH_ROUTER_CHECK_ATTEMPTS` which was not respected (`#427 <https://github.com/ros2/rmw_zenoh/issues/427>`_)
* fix: use the default destructor to drop the member `Payload` (`#419 <https://github.com/ros2/rmw_zenoh/issues/419>`_)
* Remove `gid_hash\_` from `AttachmentData` (`#416 <https://github.com/ros2/rmw_zenoh/issues/416>`_)
* Sync the config with the default config in Zenoh. (`#396 <https://github.com/ros2/rmw_zenoh/issues/396>`_)
* fix: check the context validity before accessing the session (`#403 <https://github.com/ros2/rmw_zenoh/issues/403>`_)
* Fix wan't typo (`#400 <https://github.com/ros2/rmw_zenoh/issues/400>`_)
* Contributors: ChenYing Kuo (CY), Chris Lalancette, Julien Enoch, Mahmoud Mazouz, Tim Clephas, Yuyuan Yuan, Yadunund

0.3.0 (2025-01-02)
------------------
* An alternative middleware for ROS 2 based on Zenoh.
* Contributors: Alejandro Hernández Cordero, Alex Day, Bernd Pfrommer, ChenYing Kuo (CY), Chris Lalancette, Christophe Bedard, CihatAltiparmak, Esteve Fernandez, Franco Cipollone, Geoffrey Biggs, Hans-Martin, James Mount, Julien Enoch, Morgan Quigley, Nate Koenig, Shivang Vijay, Yadunund, Yuyuan Yuan, methylDragon
* Contributors: Alejandro Hernández Cordero, Alex Day, Bernd Pfrommer, ChenYing Kuo (CY), Chris Lalancette, Christophe Bedard, CihatAltiparmak, Esteve Fernandez, Franco Cipollone, Geoffrey Biggs, Hans-Martin, James Mount, Julien Enoch, Morgan Quigley, Nate Koenig, Shivang Vijay, Yadunund, Yuyuan Yuan, methylDragon
5 changes: 2 additions & 3 deletions rmw_zenoh_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,11 @@ find_package(rcutils REQUIRED)
find_package(rosidl_typesupport_fastrtps_c REQUIRED)
find_package(rosidl_typesupport_fastrtps_cpp REQUIRED)
find_package(rmw REQUIRED)
find_package(rmw_dds_common REQUIRED)
find_package(rmw_security_common REQUIRED)
find_package(tracetools REQUIRED)
find_package(zenoh_cpp_vendor REQUIRED)

if(SECURITY)
find_package(OpenSSL REQUIRED)
set(HAVE_SECURITY 1)
endif()

Expand Down Expand Up @@ -74,7 +73,7 @@ target_link_libraries(rmw_zenoh_cpp
rosidl_typesupport_fastrtps_c::rosidl_typesupport_fastrtps_c
rosidl_typesupport_fastrtps_cpp::rosidl_typesupport_fastrtps_cpp
rmw::rmw
rmw_dds_common::rmw_dds_common_library
rmw_security_common::rmw_security_common_library
tracetools::tracetools
zenohcxx::zenohc
)
Expand Down
49 changes: 35 additions & 14 deletions rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5
Original file line number Diff line number Diff line change
Expand Up @@ -135,11 +135,11 @@
/// Accepts a single value (e.g. autoconnect: ["router", "peer"])
/// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }).
/// Each value is a list of: "peer", "router" and/or "client".
autoconnect: { router: [], peer: ["router", "peer"] },
autoconnect: { router: [], peer: ["router", "peer"], client: ["router"] },
/// Whether or not to listen for scout messages on UDP multicast and reply to them.
listen: true,
},
/// The gossip scouting configuration.
/// The gossip scouting configuration. Note that instances in "client" mode do not participate in gossip.
gossip: {
/// Whether gossip scouting is enabled or not
enabled: true,
Expand All @@ -149,10 +149,17 @@
/// It mostly makes sense when using "linkstate" routing mode where all nodes in the subsystem don't have
/// direct connectivity with each other.
multihop: false,
/// Which type of Zenoh instances to send gossip messages to.
/// Accepts a single value (e.g. target: ["router", "peer"]) which applies whatever the configured "mode" is,
/// or different values for router or peer mode (e.g. target: { router: ["router", "peer"], peer: ["router"] }).
/// Each value is a list of "peer" and/or "router".
/// ROS setting: by default all peers rely on the router to discover each other. Thus configuring the peer to send gossip
/// messages only to the router is sufficient and avoids unecessary traffic between Nodes at launch time.
target: { router: ["router", "peer"], peer: ["router"]},
/// Which type of Zenoh instances to automatically establish sessions with upon discovery on gossip.
/// Accepts a single value (e.g. autoconnect: ["router", "peer"])
/// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }).
/// Each value is a list of: "peer", "router" and/or "client".
/// or different values for router or peer mode (e.g. autoconnect: { router: [], peer: ["router", "peer"] }).
/// Each value is a list of: "peer" and/or "router".
autoconnect: { router: [], peer: ["router", "peer"] },
},
},
Expand Down Expand Up @@ -191,6 +198,14 @@
/// The routing strategy to use in peers. ("peer_to_peer" or "linkstate").
mode: "peer_to_peer",
},
/// The interests-based routing configuration.
/// This configuration applies regardless of the mode (router, peer or client).
interests: {
/// The timeout to wait for incoming interests declarations in milliseconds.
/// The expiration of this timeout implies that the discovery protocol might be incomplete,
/// leading to potential loss of messages, queries or liveliness tokens.
timeout: 10000,
},
},

// /// Overwrite QoS options for Zenoh messages by key expression (ignores Zenoh API QoS config for overwritten values)
Expand Down Expand Up @@ -343,11 +358,11 @@
open_timeout: 10000,
/// Timeout in milliseconds when accepting a link
accept_timeout: 10000,
/// Maximum number of zenoh session in pending state while accepting
/// Maximum number of links in pending state while performing the handshake for accepting it
accept_pending: 100,
/// Maximum number of sessions that can be simultaneously alive
/// Maximum number of transports that can be simultaneously alive for a single zenoh sessions
max_sessions: 1000,
/// Maximum number of incoming links that are admitted per session
/// Maximum number of incoming links that are admitted per transport
max_links: 1,
/// Enables the LowLatency transport
/// This option does not make LowLatency transport mandatory, the actual implementation of transport
Expand Down Expand Up @@ -429,14 +444,14 @@
/// then amount of memory being allocated for each queue is SIZE_XXX * LINK_MTU.
/// If qos is false, then only the DATA priority will be allocated.
size: {
control: 1,
real_time: 1,
interactive_high: 1,
interactive_low: 1,
control: 2,
real_time: 2,
interactive_high: 2,
interactive_low: 2,
data_high: 2,
data: 4,
data_low: 4,
background: 4,
data: 2,
data_low: 2,
background: 2,
},
/// Congestion occurs when the queue is empty (no available batch).
congestion_control: {
Expand Down Expand Up @@ -464,6 +479,12 @@
/// The maximum time limit (in ms) a message should be retained for batching when back-pressure happens.
time_limit: 1,
},
allocation: {
/// Mode for memory allocation of batches in the priority queues.
/// - "init": batches are allocated at queue initialization time.
/// - "lazy": batches are allocated when needed up to the maximum number of batches configured in the size configuration parameter.
mode: "lazy",
},
},
},
/// Configure the zenoh RX parameters of a link
Expand Down
49 changes: 35 additions & 14 deletions rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5
Original file line number Diff line number Diff line change
Expand Up @@ -140,11 +140,11 @@
/// Accepts a single value (e.g. autoconnect: ["router", "peer"])
/// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }).
/// Each value is a list of: "peer", "router" and/or "client".
autoconnect: { router: [], peer: ["router", "peer"] },
autoconnect: { router: [], peer: ["router", "peer"], client: ["router"] },
/// Whether or not to listen for scout messages on UDP multicast and reply to them.
listen: true,
},
/// The gossip scouting configuration.
/// The gossip scouting configuration. Note that instances in "client" mode do not participate in gossip.
gossip: {
/// Whether gossip scouting is enabled or not
enabled: true,
Expand All @@ -154,10 +154,17 @@
/// It mostly makes sense when using "linkstate" routing mode where all nodes in the subsystem don't have
/// direct connectivity with each other.
multihop: false,
/// Which type of Zenoh instances to send gossip messages to.
/// Accepts a single value (e.g. target: ["router", "peer"]) which applies whatever the configured "mode" is,
/// or different values for router or peer mode (e.g. target: { router: ["router", "peer"], peer: ["router"] }).
/// Each value is a list of "peer" and/or "router".
/// ROS setting: by default all peers rely on the router to discover each other. Thus configuring the peer to send gossip
/// messages only to the router is sufficient and avoids unecessary traffic between Nodes at launch time.
target: { router: ["router", "peer"], peer: ["router"]},
/// Which type of Zenoh instances to automatically establish sessions with upon discovery on gossip.
/// Accepts a single value (e.g. autoconnect: ["router", "peer"])
/// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }).
/// Each value is a list of: "peer", "router" and/or "client".
/// or different values for router or peer mode (e.g. autoconnect: { router: [], peer: ["router", "peer"] }).
/// Each value is a list of: "peer" and/or "router".
autoconnect: { router: [], peer: ["router", "peer"] },
},
},
Expand Down Expand Up @@ -194,6 +201,14 @@
/// The routing strategy to use in peers. ("peer_to_peer" or "linkstate").
mode: "peer_to_peer",
},
/// The interests-based routing configuration.
/// This configuration applies regardless of the mode (router, peer or client).
interests: {
/// The timeout to wait for incoming interests declarations in milliseconds.
/// The expiration of this timeout implies that the discovery protocol might be incomplete,
/// leading to potential loss of messages, queries or liveliness tokens.
timeout: 10000,
},
},

// /// Overwrite QoS options for Zenoh messages by key expression (ignores Zenoh API QoS config for overwritten values)
Expand Down Expand Up @@ -346,11 +361,11 @@
open_timeout: 10000,
/// Timeout in milliseconds when accepting a link
accept_timeout: 10000,
/// Maximum number of zenoh session in pending state while accepting
/// Maximum number of links in pending state while performing the handshake for accepting it
accept_pending: 100,
/// Maximum number of sessions that can be simultaneously alive
/// Maximum number of transports that can be simultaneously alive for a single zenoh sessions
max_sessions: 1000,
/// Maximum number of incoming links that are admitted per session
/// Maximum number of incoming links that are admitted per transport
max_links: 1,
/// Enables the LowLatency transport
/// This option does not make LowLatency transport mandatory, the actual implementation of transport
Expand Down Expand Up @@ -432,14 +447,14 @@
/// then amount of memory being allocated for each queue is SIZE_XXX * LINK_MTU.
/// If qos is false, then only the DATA priority will be allocated.
size: {
control: 1,
real_time: 1,
interactive_high: 1,
interactive_low: 1,
control: 2,
real_time: 2,
interactive_high: 2,
interactive_low: 2,
data_high: 2,
data: 4,
data_low: 4,
background: 4,
data: 2,
data_low: 2,
background: 2,
},
/// Congestion occurs when the queue is empty (no available batch).
congestion_control: {
Expand Down Expand Up @@ -467,6 +482,12 @@
/// The maximum time limit (in ms) a message should be retained for batching when back-pressure happens.
time_limit: 1,
},
allocation: {
/// Mode for memory allocation of batches in the priority queues.
/// - "init": batches are allocated at queue initialization time.
/// - "lazy": batches are allocated when needed up to the maximum number of batches configured in the size configuration parameter.
mode: "lazy",
},
},
},
/// Configure the zenoh RX parameters of a link
Expand Down
4 changes: 2 additions & 2 deletions rmw_zenoh_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rmw_zenoh_cpp</name>
<version>0.3.0</version>
<version>0.3.1</version>
<description>A ROS 2 middleware implementation using zenoh-cpp</description>
<maintainer email="[email protected]">Yadunund</maintainer>

Expand All @@ -25,7 +25,7 @@
<depend>rosidl_typesupport_fastrtps_c</depend>
<depend>rosidl_typesupport_fastrtps_cpp</depend>
<depend>rmw</depend>
<depend>rmw_dds_common</depend>
<depend>rmw_security_common</depend>
<depend>tracetools</depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
Loading
Loading