Skip to content

Commit

Permalink
Support ROS_AUTOMATIC_DISCOVERY_RANGE and ROS_STATIC_PEERS (#334)
Browse files Browse the repository at this point in the history
Signed-off-by: ChenYing Kuo <[email protected]>
  • Loading branch information
evshary authored Nov 25, 2024
1 parent 2d04729 commit 864a532
Show file tree
Hide file tree
Showing 8 changed files with 275 additions and 28 deletions.
34 changes: 34 additions & 0 deletions Cargo.lock

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

1 change: 1 addition & 0 deletions Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ regex = "1.7.1"
rustc_version = "0.4"
serde = "1.0.154"
serde_json = "1.0.114"
test-case = { version = "3.3.1" }
tokio = { version = "1.35.1", default-features = false } # Default features are disabled due to some crates' requirements
tracing = "0.1"
zenoh = { version = "1.0.0-dev", git = "https://github.com/eclipse-zenoh/zenoh.git", branch = "main", features = [
Expand Down
22 changes: 22 additions & 0 deletions DEFAULT_CONFIG.json5
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,28 @@
////
// ros_localhost_only: true,

////
//// ros_automatic_discovery_range: controls how far ROS nodes will try to discover each other.
//// Valid options are:
//// * "SUBNET" is the default, and for DDS based middleware it means it will discover any node reachable via multicast.
//// * "LOCALHOST" means a node will only try to discover other nodes on the same machine.
//// * "OFF" means the node won’t discover any other nodes, even on the same machine.
//// * "SYSTEM_DEFAULT" means “don’t change any discovery settings”.
////
//// Note that this is only available with ROS 2 Iron and later version
//// For more information: https://docs.ros.org/en/rolling/Tutorials/Advanced/Improved-Dynamic-Discovery.html
////
// ros_automatic_discovery_range: "SUBNET",

////
//// ros_static_peers: is a semicolon (;) separated list of addresses that ROS should try to discover nodes on.
//// This allows connecting to nodes on specific machines (as long as their discovery range is not set to OFF).
////
//// Note that this is only available with ROS 2 Iron and later version
//// For more information: https://docs.ros.org/en/rolling/Tutorials/Advanced/Improved-Dynamic-Discovery.html
////
// ros_static_peers: "192.168.1.1;192.168.1.2",

////
//// shm_enabled: If set to true, the DDS implementation will use Iceoryx shared memory.
//// Requires the bridge to be built with the 'dds_shm' feature for this option to valid.
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ A typical usage is to run 1 bridge in a robot, and 1 bridge in another host moni
It's important to make sure that NO DDS communication can occur between 2 hosts that are bridged by `zenoh-bridge-ros2dds`. Otherwise, some duplicate or looping traffic can occur.
To make sure of this, you can either:

- define `ROS_LOCALHOST_ONLY=1`.
- use ROS_AUTOMATIC_DISCOVERY_RANGE=LOCALHOST after Iron and ROS_LOCALHOST_ONLY=1 before Iron.
Preferably, enable MULTICAST on the loopback interface with this command (on Linux): `sudo ip l set lo multicast on`
- use different `ROS_DOMAIN_ID` on each hosts
- use a `CYCLONEDDS_URI` that configures CycloneDDS to only use internal interfaces to the robot. This configuration has to be used for all ROS Nodes as well as for the bridge.
Expand Down
16 changes: 16 additions & 0 deletions zenoh-bridge-ros2dds/src/bridge_args.rs
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,12 @@ pub struct BridgeArgs {
verbatim_doc_comment
)]
pub ros_localhost_only: bool,
/// Configure CycloneDDS to apply ROS_AUTOMATIC_DISCOVREY_RANGE. The argument only takes effect after ROS 2 Iron.
#[arg(long, env("ROS_AUTOMATIC_DISCOVERY_RANGE"))]
pub ros_automatic_discovery_range: Option<String>,
/// Configure CycloneDDS to apply ROS_STATIC_PEERS. The argument only takes effect after ROS 2 Iron.
#[arg(long, env("ROS_STATIC_PEERS"))]
pub ros_static_peers: Option<String>,
/// 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)]
Expand Down Expand Up @@ -101,6 +107,16 @@ impl From<&BridgeArgs> for Config {
"plugins/ros2dds/ros_localhost_only",
&args.ros_localhost_only,
);
insert_json5_option(
&mut config,
"plugins/ros2dds/ros_automatic_discovery_range",
&args.ros_automatic_discovery_range,
);
insert_json5_option(
&mut config,
"plugins/ros2dds/ros_static_peers",
&args.ros_static_peers,
);
#[cfg(feature = "dds_shm")]
{
insert_json5(
Expand Down
1 change: 1 addition & 0 deletions zenoh-plugin-ros2dds/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ lazy_static = { workspace = true }
regex = { workspace = true }
serde = { workspace = true }
serde_json = { workspace = true }
test-case = { workspace = true }
tokio = { workspace = true }
tracing = { workspace = true }
zenoh = { workspace = true }
Expand Down
95 changes: 94 additions & 1 deletion zenoh-plugin-ros2dds/src/config.rs
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,13 @@ pub struct Config {
pub domain: u32,
#[serde(default = "default_localhost_only")]
pub ros_localhost_only: bool,
#[serde(
default = "default_automatic_discovery_range",
deserialize_with = "deserialize_automatic_discovery_range"
)]
pub ros_automatic_discovery_range: Option<RosAutomaticDiscoveryRange>,
#[serde(default, deserialize_with = "deserialize_static_peers")]
pub ros_static_peers: Option<Vec<String>>,
#[serde(default, flatten)]
pub allowance: Option<Allowance>,
#[serde(
Expand Down Expand Up @@ -466,10 +473,63 @@ fn default_reliable_routes_blocking() -> bool {
DEFAULT_RELIABLE_ROUTES_BLOCKING
}

#[derive(Deserialize, Debug, Serialize, Eq, PartialEq, Clone, Copy)]
pub enum RosAutomaticDiscoveryRange {
Subnet,
Localhost,
Off,
SystemDefault,
}

fn default_localhost_only() -> bool {
env::var("ROS_LOCALHOST_ONLY").as_deref() == Ok("1")
}

fn default_automatic_discovery_range() -> Option<RosAutomaticDiscoveryRange> {
Some(match env::var("ROS_AUTOMATIC_DISCOVERY_RANGE").as_deref() {
Ok("LOCALHOST") => RosAutomaticDiscoveryRange::Localhost,
Ok("OFF") => RosAutomaticDiscoveryRange::Localhost,
Ok("SYSTEM_DEFAULT") => RosAutomaticDiscoveryRange::SystemDefault,
_ => RosAutomaticDiscoveryRange::Subnet,
})
}

fn deserialize_automatic_discovery_range<'de, D>(
deserializer: D,
) -> Result<Option<RosAutomaticDiscoveryRange>, D::Error>
where
D: Deserializer<'de>,
{
let discovery_range: String = Deserialize::deserialize(deserializer).unwrap();
match discovery_range.as_str() {
"SUBNET" => Ok(Some(RosAutomaticDiscoveryRange::Subnet)),
"LOCALHOST" => Ok(Some(RosAutomaticDiscoveryRange::Localhost)),
"OFF" => Ok(Some(RosAutomaticDiscoveryRange::Off)),
"SYSTEM_DEFAULT" => Ok(Some(RosAutomaticDiscoveryRange::SystemDefault)),
unknown => Err(de::Error::custom(format!(
r#"Invalid parameter {unknown} for ROS_AUTOMATICALLY_DISCOVERY_RANGE"#
))),
}
}

fn deserialize_static_peers<'de, D>(deserializer: D) -> Result<Option<Vec<String>>, D::Error>
where
D: Deserializer<'de>,
{
let peers: String = Deserialize::deserialize(deserializer).unwrap();
let mut peer_list: Vec<String> = Vec::new();
for peer in peers.split(';') {
if peer != "" {
peer_list.push(peer.to_owned());
}
}
if peer_list.is_empty() {
Ok(None)
} else {
Ok(Some(peer_list))
}
}

fn default_transient_local_cache_multiplier() -> usize {
DEFAULT_TRANSIENT_LOCAL_CACHE_MULTIPLIER
}
Expand Down Expand Up @@ -648,7 +708,9 @@ where

#[cfg(test)]
mod tests {
use super::Config;
use test_case::test_case;

use super::{Config, RosAutomaticDiscoveryRange};

#[test]
fn test_allowance() {
Expand Down Expand Up @@ -862,4 +924,35 @@ mod tests {
assert_eq!(__path__, None);
assert_eq!(__required__, None);
}

#[test_case("{}", Some(RosAutomaticDiscoveryRange::Subnet); "Empty tests")]
#[test_case(r#"{"ros_automatic_discovery_range": "SUBNET"}"#, Some(RosAutomaticDiscoveryRange::Subnet); "SUBNET tests")]
#[test_case(r#"{"ros_automatic_discovery_range": "LOCALHOST"}"#, Some(RosAutomaticDiscoveryRange::Localhost); "LOCALHOST tests")]
#[test_case(r#"{"ros_automatic_discovery_range": "OFF"}"#, Some(RosAutomaticDiscoveryRange::Off); "OFF tests")]
#[test_case(r#"{"ros_automatic_discovery_range": "SYSTEM_DEFAULT"}"#, Some(RosAutomaticDiscoveryRange::SystemDefault); "SYSTEM_DEFAULT tests")]
fn test_ros_automatic_discovery_range(
config: &str,
result: Option<RosAutomaticDiscoveryRange>,
) {
let config = serde_json::from_str::<Config>(config);
println!(">>> {:?}", config);
assert!(config.is_ok());
let Config {
ros_automatic_discovery_range,
..
} = config.unwrap();
assert_eq!(ros_automatic_discovery_range, result);
}

#[test_case("{}", None; "Empty tests")]
#[test_case(r#"{"ros_static_peers": "127.0.0.1"}"#, Some(vec!["127.0.0.1".to_owned()]); "Single peer")]
#[test_case(r#"{"ros_static_peers": "192.168.1.1;192.168.1.2"}"#, Some(vec!["192.168.1.1".to_owned(), "192.168.1.2".to_owned()]); "Multiple peers")]
fn test_ros_static_peers(config: &str, result: Option<Vec<String>>) {
let config = serde_json::from_str::<Config>(config);
assert!(config.is_ok());
let Config {
ros_static_peers, ..
} = config.unwrap();
assert_eq!(ros_static_peers, result);
}
}
Loading

0 comments on commit 864a532

Please sign in to comment.