diff --git a/README.md b/README.md index d0363d2..4a1e6af 100644 --- a/README.md +++ b/README.md @@ -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. diff --git a/zenoh-plugin-ros2dds/src/config.rs b/zenoh-plugin-ros2dds/src/config.rs index 3b7b6b4..0579aba 100644 --- a/zenoh-plugin-ros2dds/src/config.rs +++ b/zenoh-plugin-ros2dds/src/config.rs @@ -501,15 +501,15 @@ where D: Deserializer<'de>, { let discovery_range: String = Deserialize::deserialize(deserializer).unwrap(); - Ok(Some(match discovery_range.as_str() { - "SUBNET" => RosAutomaticDiscoveryRange::Subnet, - "LOCALHOST" => RosAutomaticDiscoveryRange::Localhost, - "OFF" => RosAutomaticDiscoveryRange::Off, - "SYSTEM_DEFAULT" => RosAutomaticDiscoveryRange::SystemDefault, - unknown => { - panic!(r#"Invalid parameter {unknown} for ROS_AUTOMATICALLY_DISCOVERY_RANGE"#) - } - })) + 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>, D::Error> @@ -528,7 +528,6 @@ where } else { Ok(Some(peer_list)) } - //deserializer.deserialize_option(OptPathVisitor) } fn default_transient_local_cache_multiplier() -> usize { diff --git a/zenoh-plugin-ros2dds/src/lib.rs b/zenoh-plugin-ros2dds/src/lib.rs index 1f8bab8..d72208f 100644 --- a/zenoh-plugin-ros2dds/src/lib.rs +++ b/zenoh-plugin-ros2dds/src/lib.rs @@ -303,6 +303,14 @@ pub async fn run(runtime: Runtime, config: Config) { // Dynamic Discovery is changed after iron. Need to check the ROS 2 version. // https://docs.ros.org/en/rolling/Tutorials/Advanced/Improved-Dynamic-Discovery.html if ros_distro_is_less_than("iron") { + if config.ros_automatic_discovery_range.is_some() { + tracing::warn!("ROS_AUTOMATIC_DISCOVERY_RANGE will be ignored since it's not supported before ROS 2 Iron"); + } + if config.ros_static_peers.is_some() { + tracing::warn!( + "ROS_STATIC_PEERS will be ignored since it's not supported before ROS 2 Iron" + ); + } // if "ros_localhost_only" is set, configure CycloneDDS to use only localhost interface if config.ros_localhost_only { env::set_var( @@ -318,6 +326,8 @@ pub async fn run(runtime: Runtime, config: Config) { let (ros_automatic_discovery_range, ros_static_peers) = if config.ros_localhost_only { // If ROS_LOCALHOST_ONLY is set, need to transform into new environmental variables // Refer to https://github.com/ros2/ros2_documentation/pull/3519#discussion_r1186541935 + tracing::warn!("ROS_LOCALHOST_ONLY is deprecated but still honored if it is enabled. Use ROS_AUTOMATIC_DISCOVERY_RANGE and ROS_STATIC_PEERS instead."); + tracing::warn!("'localhost_only' is enabled, 'automatic_discovery_range' and 'static_peers' will be ignored."); (Some(RosAutomaticDiscoveryRange::Localhost), None) } else { (