Skip to content

Commit

Permalink
Make zenoh router configurable using envar
Browse files Browse the repository at this point in the history
Signed-off-by: Yadunund <[email protected]>
  • Loading branch information
Yadunund committed Feb 27, 2024
1 parent f090716 commit 210aec3
Show file tree
Hide file tree
Showing 6 changed files with 115 additions and 62 deletions.
45 changes: 25 additions & 20 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ source install/setup.bash
> Note: Manually launching zenoh router won't be necessary in the future.
```bash
# terminal 1
ros2 run rmw_zenoh_cpp init_rmw_zenoh_router
ros2 run rmw_zenoh_cpp 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](#config).
Expand All @@ -68,26 +68,31 @@ ros2 run demo_nodes_cpp listener
The listener node should start receiving messages over the `/chatter` topic.
> Note: Ignore all the warning printouts.
### Graph introspection
Presently we only support limited `ros2cli` commands to introspect the ROS graph such as `ros2 node list` and `ros2 topic list`.
## Configuration
`rmw_zenoh` relies on separate configurations files to configure the Zenoh `router` and `session` respectively. For more information on the topology of Zenoh adopted in `rmw_zenoh`, please see [Design](#design). Default configuration files are used by `rmw_zenoh` however certain environment variables may be set to provide absolute paths to custom configuration files. The table below summarizes the default files and the environment variables for the `router` and `session`. For a complete list of configurable parameters, see [zenoh/DEFAULT_CONFIG.json5](https://github.com/eclipse-zenoh/zenoh/blob/main/DEFAULT_CONFIG.json5).

## Config
The [default configuration](rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5) sets up the zenoh sessions with the following main characteristics:
| | Default config | Envar for custom config |
|---------|:----------------------------------------------------------------------------------------------------:|:--------------------------:|
| Router | [DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5](rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5) | `ZENOH_ROUTER_CONFIG_URI` |
| Session | [DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5](rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5) | `ZENOH_SESSION_CONFIG_URI` |

Table:
| Zenoh Config | Default |
| :---: | :---: |
| udp_multicast | disabled |
| gossip scouting | enabled |
| connect | tcp/localhost:7447 |

This assumes that there is a `zenohd` running in the system at port 7447.
A custom configuration may be provided by setting the `RMW_ZENOH_CONFIG_FILE` environment variable to point to a custom zenoh configuration file.
For example, to set the path to a custom `router` configuration file,
```bash
export ZENOH_ROUTER_CONFIG_URI=$HOME/MY_ZENOH_ROUTER_CONFIG.json5
```

### Connecting multiple hosts
By default, all discovery traffic is local per host where host is the PC running a Zenoh `router`.
To bridge communications across two hosts, the `router` configuration for one the hosts must be updated to connect to the other `router` at startup.
This is done by specifying an endpoint in host's `router` configuration file to as seen below.
In this example, the `router` will connect to the `router` running on a second host with IP address `192.168.1.1` and port `7447`.

```json
{
connect: {
endpoints: ["tcp/192.168.1.1:7447"],
},
}
```

## TODO Features
- [x] Publisher
- [x] Subscription
- [ ] Client
- [ ] Service
- [ ] Graph introspection
> Note: To connect multiple hosts, include the endpoints of all routers in the network.
11 changes: 8 additions & 3 deletions rmw_zenoh_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -95,16 +95,21 @@ install(
DESTINATION share/${PROJECT_NAME}
)

add_executable(init_rmw_zenoh_router apps/init_rmw_zenoh_router.cpp)
add_executable(zenohd
src/zenohd/main.cpp
src/detail/zenoh_config.cpp
)

target_link_libraries(init_rmw_zenoh_router
target_link_libraries(zenohd
PRIVATE
ament_index_cpp::ament_index_cpp
rcutils::rcutils
rmw::rmw
zenohc::lib
)

install(
TARGETS init_rmw_zenoh_router
TARGETS zenohd
DESTINATION lib/${PROJECT_NAME}
)

Expand Down
67 changes: 44 additions & 23 deletions rmw_zenoh_cpp/src/detail/zenoh_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,48 +22,69 @@
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rmw/impl/cpp/macros.hpp>

#include "identifier.hpp"

///==============================================================================
namespace
{

/// Env var to set the path to the zenoh configuration file.
static constexpr const char * kZenohConfigFileEnvVar = "RMW_ZENOH_CONFIG_FILE";
/// The name of the default configuration file for the default zenoh session configuration.
static constexpr const char * const kDefaultZenohConfigFileName =
"DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5";

} // namespace
static const std::unordered_map<ConfigurableEntity, const char *> default_config_filenames = {
{ConfigurableEntity::Session, "DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5"},
{ConfigurableEntity::Router, "DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5"}
};

rmw_ret_t get_z_config(z_owned_config_t * config)
rmw_ret_t _get_z_config(
const char * envar_name,
const char * default_uri,
z_owned_config_t * config)
{
const char * zenoh_config_path;
const char * configured_uri;
const char * envar_uri;
// Get the path to the zenoh configuration file from the environment variable.
if (NULL != rcutils_get_env(kZenohConfigFileEnvVar, &zenoh_config_path)) {
if (NULL != rcutils_get_env(envar_name, &envar_uri)) {
// NULL is returned if everything is ok.
RCUTILS_LOG_ERROR_NAMED(
"ZenohConfiguration", "Env Var '%s' can't be read.", kZenohConfigFileEnvVar);
"rmw_zenoh_cpp", "Envar %s cannot be read.", envar_name);
return RMW_RET_ERROR;
}

// If the environment variable contains a path to a file, try to read the configuration from it.
if (zenoh_config_path[0] != '\0') {
if (envar_uri[0] != '\0') {
// If the environment variable is set, try to read the configuration from the file.
*config = zc_config_from_file(zenoh_config_path);
*config = zc_config_from_file(envar_uri);
configured_uri = envar_uri;
} else {
// If the environment variable is not set use internal configuration
static const std::string path_to_config_folder =
ament_index_cpp::get_package_share_directory(rmw_zenoh_identifier) + "/config/";
const std::string default_zconfig_path = path_to_config_folder + kDefaultZenohConfigFileName;
*config = zc_config_from_file(default_zconfig_path.c_str());
*config = zc_config_from_file(default_uri);
configured_uri = default_uri;
}

// Verify that the configuration is valid.
if (!z_config_check(config)) {
RCUTILS_LOG_ERROR_NAMED(
"ZenohConfiguration",
"Configuration is not valid. Please check the zenoh configuration file.");
"rmw_zenoh_cpp",
"Invalid configuration file %s", configured_uri);
return RMW_RET_ERROR;
}
RCUTILS_LOG_DEBUG_NAMED(
"rmw_zenoh_cpp",
"configured using configuration file %s", configured_uri);
return RMW_RET_OK;
}
} // namespace

///==============================================================================
rmw_ret_t get_z_config(const ConfigurableEntity & entity, z_owned_config_t * config)
{
auto entity_envar_it = envar_map.find(entity);
auto default_filename_it = default_config_filenames.find(entity);
if (entity_envar_it == envar_map.end() ||
default_filename_it == default_config_filenames.end() )
{
RCUTILS_LOG_ERROR_NAMED(
"rmw_zenoh_cpp", "get_z_config called with invalid ConfigurableEntity.");
return RMW_RET_ERROR;
}
// Get the absolute path to the default configuration file.
static const std::string path_to_config_folder =
ament_index_cpp::get_package_share_directory("rmw_zenoh_cpp") + "/config/";
const std::string default_config_path = path_to_config_folder + default_filename_it->second;

return _get_z_config(entity_envar_it->second, default_config_path.c_str(), config);
}
34 changes: 26 additions & 8 deletions rmw_zenoh_cpp/src/detail/zenoh_config.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,20 +15,38 @@
#ifndef DETAIL__ZENOH_CONFIG_HPP_
#define DETAIL__ZENOH_CONFIG_HPP_

#include <unordered_map>

#include <zenoh.h>

#include "rmw/ret_types.h"

/// Get the zenoh configuration for a session.
///==============================================================================
enum class ConfigurableEntity : uint8_t
{
Invalid = 0,
Session,
Router
};

///==============================================================================
/// Environment variable name that stores the absolute path to the Zenoh config
/// for respective entities.
static const std::unordered_map<ConfigurableEntity, const char *> envar_map = {
{ConfigurableEntity::Session, "ZENOH_SESSION_CONFIG_URI"},
{ConfigurableEntity::Router, "ZENOH_ROUTER_CONFIG_URI"}
};

/// Get the zenoh configuration for a configurable entity.
/// @details The behavior is as follows:
/// - If the environment variable `RMW_ZENOH_CONFIG_FILE` is set, it will
/// be used as the path to the zenoh configuration file.
/// - In case there is an error reading the file, the internal configuration will be used.
/// - If the environment variable `RMW_ZENOH_CONFIG_FILE` is not set, the
/// configuration will be read from the internal configuration.
/// - If internal configuration is not available, a zenoh default configuration is used.
/// - If the environment variable for the entity is set, the z_owned_config_t
/// is configured as per the configuration file retrieved.
/// - If the environment variable is not set, the z_owned_config_t
/// is configured using the rmw_zenoh default configuration file.
/// @param entity The zenoh entity to be configured.
/// @param config The zenoh configuration to be filled.
/// @returns `RMW_RET_OK` if the configuration was successfully loaded.
rmw_ret_t get_z_config(z_owned_config_t * config);
[[nodiscard]]
rmw_ret_t get_z_config(const ConfigurableEntity & entity, z_owned_config_t * config);

#endif // DETAIL__ZENOH_CONFIG_HPP_
4 changes: 2 additions & 2 deletions rmw_zenoh_cpp/src/rmw_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,8 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context)

// Initialize the zenoh configuration.
z_owned_config_t config;
if ((ret = get_z_config(&config)) != RMW_RET_OK) {
RMW_SET_ERROR_MSG("Error setting up zenoh configuration for the session.");
if ((ret = get_z_config(ConfigurableEntity::Session, &config)) != RMW_RET_OK) {
RMW_SET_ERROR_MSG("Error configuring Zenoh session.");
return ret;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,10 @@

#include <ament_index_cpp/get_package_share_directory.hpp>

#include "../detail/zenoh_config.hpp"

#include "rmw/error_handling.h"

static bool running = true;

class KeyboardReader final
Expand Down Expand Up @@ -169,13 +173,13 @@ int main(int argc, char ** argv)
(void)argc;
(void)argv;

static const char * RMW_ZENOH_IDENTIFIER = "rmw_zenoh_cpp";
static const char * ZENOH_ROUTER_CONFIG_NAME = "DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5";
const std::string zenoh_router_config_path =
ament_index_cpp::get_package_share_directory(RMW_ZENOH_IDENTIFIER) +
"/config/" + std::string(ZENOH_ROUTER_CONFIG_NAME);
// Initialize the zenoh configuration for the router.
z_owned_config_t config;
if ((get_z_config(ConfigurableEntity::Router, &config)) != RMW_RET_OK) {
RMW_SET_ERROR_MSG("Error configuring Zenoh router.");
return 1;
}

z_owned_config_t config = zc_config_from_file(zenoh_router_config_path.c_str());
z_owned_session_t s = z_open(z_move(config));
if (!z_check(s)) {
printf("Unable to open router session!\n");
Expand Down

0 comments on commit 210aec3

Please sign in to comment.