ros2-humble跨域通信方式
ros2 humble发行版目前暂知两种跨域通信方式:domain_bridge、fastdds discovery server。
注:要进行跨设备的通信需要 export ROS_LOCALHOST_ONLY=0
。
Domain Bridge
domain bridge是ros2提供的一个扩展库,默认不与ros2源码进行编译。
要使用domain_bridge来进行跨域通信,首先要下载其源码,进行编译。
Bash mkdir -p domain_bridge_ws/src && cd domain_bridge_ws
git clone -b humble https://github.com/ros2/domain_bridge.git src/
colcon build
domain_bridge的使用方式主要有两种,一个是利用cli程序加载yaml配置文件,另一个是使用domain_bridge提供的C++ API实现跨域通信。
CLI
通过ros2所提供的run与launch cli工具与yaml配置文件搭配使用,下面以run为例。
Bash ros2 run domain_bridge domain_bridge [ --from 1 --to 2 ] etc/bridge_config.yaml
其中[-- from 1 --to 2]是可选的,可以将跨域所指定的信息都写在yaml文件中,如果在命令行参数中指定了from to 域id,则其会覆盖yaml文件中所配置的域id。命令的最后需要指定yaml文件的路径。
下面是一个topic 跨域通信的bridge配置文件(目前只有topic模式支持从配置文件进行跨域通信),必须要指定的是topic_name与其中的type(可以通过 ros2 topic list -t 查看)。
YAML # Name of the domain bridge, used for node naming and logging
name : topic_bridge
from_domain : 2
to_domain : 3
topics :
# 建立topic: topic_pubsub 从域2到域3的bridge,指定qos为reliable
topic_pubsub : # topic_name
type : std_msgs/msg/String
qos :
reliability : reliable
# 该配置可以让所在的topic_pubsub topic同时进行跨域的正反向通信
# bidirectional: True
# 建立topic: chatter 从域2到域3的bridge
chatter :
type : example_interfaces/msg/String
to_domain : 4
C++ Library
domain_bridge提供了c++ 库与相应的api接口供rclcpp代码调用,这种方式支持 topic 和 service的跨域通信(action模式暂不支持)。
在使用domain_bridge的api进行编码前要先将其加入到工程配置中
在CMakeLists.txt加入
Bash find_package( domain_bridge REQUIRED)
# 在可执行文件中加入编译依赖
ament_target_dependencies( xxx domain_bridge)
在package.xml中加入
XML <depend> domain_bridge</depend>
修改工程代码
FastDDS Discovery Server
这个发现服务是由fastdds提供的,通过创建中心服务器来实现跨域通信,可有效降低设备发现时的流量。
使用方式:通过fastdds discovery cli工具进行配置。
启动discovery server
Bash # 启动服务id为0(唯一)的fastdds discovery server,默认基于端口为11811的udp
fastdds discovery -i 0
# 启动服务id为1 ip为127.0.0.1 端口为14520的udp fastdds发现服务(该服务仅能被本机的域使用)
fastdds discovery -i 1 -l 127 .0.0.1 -p 14520
# 启动服务id为2 ip为169.254.102.8 端口为15520的 udp fastdds发现服务(可被169.254.102.8所在局域网内的机器域使用)
fastdds discovery -i 2 -l 169 .254.102.8 -p 14520
# 启动服务id为3 ip为127.0.0.1 端口为42100(默认tcp端口)的tcp fastdds发现服务
fastdds discovery -i 3 -t 127 .0.0.1 -q 42100
ros2配置
在启动了fast discovery server之后,要让ros2的topic、service、action通信方式实现跨域通信,则还额外需要在所在ros2终端设置ROS_DISCOVERY_SERVER环境变量。
Bash # 设置下面的环境变量后,所有在该变量生效的环境内的ros2的通信都将通过该discovery server
export ROS_DISCOVERY_SERVER = "127.0.0.1:11811"
# 可同时绑定多个ip:port,中间用 ; 分隔(这里11811的server-id为0,12811的server-id为1)
export ROS_DISCOVERY_SERVER = "169.254.102.8:11811;168.254.102.8:12811"
# 注意,上述的 ROS_DISCOVERY_SERVER 中的ip:port-server具有顺序要求,如id为0的server必须在第一个位置,id为1的server必须在第二个位置。
# 如果指向绑定id为1的server,不想绑定id为0的server,则需要将id为0的server的位置空出,如 export ROS_DISCOVERY_SERVER=";168.254.102.8:12811"
跨域通信使用
在正确进行了上述的配置之后,可以通过ros2的publisher/subscriber demo进行验证。
Bash # 在进行下面的操作前要确保
# 1. discovery server已启动完毕,且server可被下面的终端访问到
# 2. 下面的终端上均设置了对应的 ROS_DISCOVERY_SERVER 变量
# 下面假定已启动ip为169.254.102.8 port为11811 server-id为0的fastdds discovery server
# 在终端1上,配置所需要的domain_id与discovery_server
export ROS_DISCOVERY_SERVER = "169.254.102.8:11811"
export ROS_DOMAIN_ID = 1
ros2 run demo_nodes_cpp talker
# 在终端2上,配置所需要的domain_id与discovery_server
export ROS_DISCOVERY_SERVER = "169.254.102.8:11811"
export ROS_DOMAIN_ID = 2
ros2 run demo_nodes_cpp listener
# 在终端3上,配置所需要的domain_id与discovery_server
export ROS_DISCOVERY_SERVER = "169.254.102.8:11811"
export ROS_DOMAIN_ID = 3
ros2 run demo_nodes_cpp listener
# 正确配置后,终端1的talker发送的消息可跨域被终端2和终端3的listener接收到
二者特点
domain_bridge:
domain_bridge是一个ros2提供的独立软件包,topic跨域通信通过利用订阅者和发布者的socket通信来实现,建立在ros2本身的通信机制之上。
domain_bridge可以**细化要跨域通信的参数**,指定某个/某些topic通过bridge进行跨域通信。
domain_bridge提供cli工具程序与c++ api接口,使用上相对灵活。
domain_bridge由于是建立在ros2的通信机制之上,所以其通信方式可以直接被ros2 cli 工具观察到(在涉及的域环境内,通过ros2 node list可以看到建立的bridge节点;通过rqt_graph可以观察到域内节点排布域连接信息)
但domain_bridge是在系统中引入额外的通信域和节点,会增加系统管理的难度。
fastdds discovery server:
fastdds discovery server采用分布式的发现机制,可快速在节点间建立通信,可以利用分布式的特性进行冗余配置和负载均衡,增加系统的可靠性和容错性。
fastdds discovery server支持ros2 topic、service、action三种通信方式的跨域通信,而domain_bridge yaml配置文件目前只支持topic、c++ api只支持topic、service的跨域通信。
但fastdds discovery server需要维护discovery server,相比domain_bridge系统资源会更高。
由于fastdds discovery server使用了中心服务器来管理跨域通信,所以通过原本的ros2 cli工具无法监测到相关节点信息,需要将ros2 daemon配置为superclient来监测,见 四、FastDDS Discovery Server补充 )
fastdds discovery server是通信域层面的跨域通信,不能进行像domain_bridge一样使限定某个topic才进行跨域通信的配置。
FastDDS Dicovery Server补充
要通过ros2 cli工具观察通过fastdds discovery server通信的节点信息,需要将ros2 daemon配置为super client,具体配置方式可通过一个xml配置文件和FASTRTPS_DEFAULT_PROFILES_FILE环境变量实现
XML <?xml version="1.0" encoding="UTF-8" ?>
<dds>
<profiles xmlns= "http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<participant profile_name= "super_client_profile" is_default_profile= "true" >
<rtps>
<builtin>
<discovery_config>
<discoveryProtocol> SUPER_CLIENT</discoveryProtocol>
<discoveryServersList>
<RemoteServer prefix= "44.53.00.5f.45.50.52.4f.53.49.4d.41" >
<metatrafficUnicastLocatorList>
<locator>
<udpv4>
<address> 127.0.0.1</address>
<port> 11811</port>
</udpv4>
</locator>
</metatrafficUnicastLocatorList>
</RemoteServer>
</discoveryServersList>
</discovery_config>
</builtin>
</rtps>
</participant>
</profiles>
</dds>
在上述的xml文件中,需要配置的信息在通过fastdds discovery启动server的时候会在终端输出。
Bash $ fastdds discovery -i 0 -l 127 .0.0.1 -p 11811
### Server is running ###
Participant Type: SERVER
Security: NO
Server ID: 0
Server GUID prefix: 44 .53.00.5f.45.50.52.4f.53.49.4d.41
Server Addresses: UDPv4:[ 127 .0.0.1] :11811
写好xml文件后,需要配置FASTRTPS_DEFAULT_PROFILES_FILE以及重启ros2 daemon进程
Bash export FASTRTPS_DEFAULT_PROFILES_FILE = super_client_configuration_file.xml
ros2 daemon stop
ros2 daemon start
# 接下来可以通过ros2 cli 工具查看通过discovery_server通信的节点信息
ros2 topic list
ros2 node list
rqt_graph