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

Bump to clap 4.4 #49

Merged
merged 2 commits into from
Jan 9, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
73 changes: 9 additions & 64 deletions Cargo.lock

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

2 changes: 1 addition & 1 deletion Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ async-std = "=1.12.0"
async-trait = "0.1.66"
bincode = "1.3.3"
cdr = "0.2.4"
clap = "3.2.23"
clap = "4.4.11"
cyclors = "0.2.0"
derivative = "2.2.0"
env_logger = "0.10.0"
Expand Down
5 changes: 3 additions & 2 deletions zenoh-bridge-ros2dds/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,13 @@ dds_shm = ["zenoh-plugin-ros2dds/dds_shm"]
[dependencies]
async-std = { workspace = true, features = ["unstable", "attributes"] }
async-liveliness-monitor = { workspace = true }
clap = { workspace = true }
clap = { workspace = true, features = ["derive", "env"] }
env_logger = { workspace = true }
lazy_static = { workspace = true }
log = { workspace = true }
serde = { workspace = true }
serde_json = { workspace = true }
zenoh = { workspace = true }
zenoh = { workspace = true }
zenoh-plugin-rest = { workspace = true }
zenoh-plugin-trait = { workspace = true }
zenoh-plugin-ros2dds = { path = "../zenoh-plugin-ros2dds/", default-features = false }
Expand Down
151 changes: 151 additions & 0 deletions zenoh-bridge-ros2dds/src/bridge_args.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
//
// Copyright (c) 2022 ZettaScale Technology
//
// This program and the accompanying materials are made available under the
// terms of the Eclipse Public License 2.0 which is available at
// http://www.eclipse.org/legal/epl-2.0, or the Apache License, Version 2.0
// which is available at https://www.apache.org/licenses/LICENSE-2.0.
//
// SPDX-License-Identifier: EPL-2.0 OR Apache-2.0
//
// Contributors:
// ZettaScale Zenoh Team, <[email protected]>
//
use crate::zenoh_args::CommonArgs;
use clap::builder::FalseyValueParser;
use zenoh::config::Config;
use zenoh::prelude::*;

//
// All Bridge arguments
//
#[derive(clap::Parser, Clone, Debug)]
#[command(version=zenoh_plugin_ros2dds::GIT_VERSION,
long_version=zenoh_plugin_ros2dds::LONG_VERSION.as_str(),
about="Zenoh bridge for ROS 2 with a DDS RMW",
)]
pub struct BridgeArgs {
#[command(flatten)]
pub session_args: CommonArgs,
/// The identifier (as an hexadecimal string, with odd number of chars - e.g.: 0A0B23...) that zenohd must use.
/// WARNING: this identifier must be unique in the system and must be 16 bytes maximum (32 chars)!
/// If not set, a random UUIDv4 will be used.
#[arg(short, long, verbatim_doc_comment)]
pub id: Option<String>,
/// A ROS 2 namespace to be used by the "zenoh_bridge_dds" node'
#[arg(short, long)]
pub namespace: Option<String>,
/// The DDS Domain ID. Default to $ROS_DOMAIN_ID environment variable if defined, or to 0 otherwise.
#[arg(short, long, default_value("0"), env("ROS_DOMAIN_ID"))]
pub domain: u32,
/// Configure CycloneDDS to use only the localhost interface. If not set, a $ROS_LOCALHOST_ONLY=1 environment variable activates this option.
/// When this flag is not active, CycloneDDS will pick the interface defined in "$CYCLONEDDS_URI" configuration, or automatically choose one.
#[arg(
long,
env("ROS_LOCALHOST_ONLY"),
value_parser(FalseyValueParser::new()),
verbatim_doc_comment
)]
pub ros_localhost_only: bool,
/// Configure CycloneDDS to use Iceoryx shared memory. If not set, CycloneDDS will instead use any shared memory settings defined in "$CYCLONEDDS_URI" configuration.
#[cfg(feature = "dds_shm")]
#[arg(long)]
pub dds_enable_shm: bool,
/// Specifies a maximum frequency of publications routing over zenoh for a set of Publishers.
/// The string must have the format "<regex>=<float>":
/// - "regex" is a regular expression matching a Publisher interface name
/// - "float" is the maximum frequency in Hertz; if publication rate is higher, downsampling will occur when routing.
/// Repeat this option to configure several topics expressions with a max frequency.
#[arg(long, value_name = "REGEX=FLOAT", verbatim_doc_comment)]
pub pub_max_frequency: Vec<String>,
/// A float in seconds that will be used as a timeout when the bridge queries any other remote bridge
/// for discovery information and for historical data for TRANSIENT_LOCAL DDS Readers it serves
/// (i.e. if the query to the remote bridge exceed the timeout, some historical samples might be not routed to the Readers, but the route will not be blocked forever).
/// This value overwrites the value possibly set in configuration file under 'plugins/ros2dds/queries_timeout/default' key [default: 5.0].
#[arg(long, value_name = "FLOAT", verbatim_doc_comment)]
pub queries_timeout_default: Option<f32>,

/// Configures HTTP interface for the REST API (disabled by default, setting this option enables it). Accepted values:
/// - a port number
/// - a string with format `<local_ip>:<port_number>` (to bind the HTTP server to a specific interface).
#[arg(short, long, value_name = "PORT | IP:PORT", verbatim_doc_comment)]
pub rest_http_port: Option<String>,
/// Experimental!! Run a watchdog thread that monitors the bridge's async executor and
/// reports as error log any stalled status during the specified period [default: 1.0 second]
#[arg(short, long, value_name = "FLOAT", default_missing_value = "1.0")]
pub watchdog: Option<Option<f32>>,
}

impl From<BridgeArgs> for Config {
fn from(value: BridgeArgs) -> Self {
(&value).into()
}
}

impl From<&BridgeArgs> for Config {
fn from(args: &BridgeArgs) -> Self {
let mut config = (&args.session_args).into();

insert_json5_option(&mut config, "plugins/ros2dds/id", &args.id);
insert_json5_option(&mut config, "plugins/ros2dds/namespace", &args.namespace);
insert_json5(&mut config, "plugins/ros2dds/domain", &args.domain);
insert_json5(
&mut config,
"plugins/ros2dds/ros_localhost_only",
&args.ros_localhost_only,
);
#[cfg(feature = "dds_shm")]
{
insert_json5(
&mut config,
"plugins/ros2dds/shm_enabled",
&args.dds_enable_shm,
);
}
insert_json5_list(
&mut config,
"plugins/ros2dds/pub_max_frequencies",
&args.pub_max_frequency,
);
insert_json5_option(
&mut config,
"plugins/ros2dds/queries_timeout/default",
&args.queries_timeout_default,
);

insert_json5_option(&mut config, "plugins/rest/http_port", &args.rest_http_port);

config
}
}

fn insert_json5<T>(config: &mut Config, key: &str, value: &T)
where
T: Sized + serde::Serialize,
{
config
.insert_json5(key, &serde_json::to_string(value).unwrap())
.unwrap();
}

fn insert_json5_option<T>(config: &mut Config, key: &str, value: &Option<T>)
where
T: Sized + serde::Serialize,
{
if let Some(v) = value {
config
.insert_json5(key, &serde_json::to_string(v).unwrap())
.unwrap();
}
}

fn insert_json5_list<T>(config: &mut Config, key: &str, values: &Vec<T>)
where
T: Sized + serde::Serialize,
{
if !values.is_empty() {
config
.insert_json5(key, &serde_json::to_string(values).unwrap())
.unwrap();
}
}
Loading