小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
《ROS 2多协议传输控制器》使用 micro-ROS 协议+USB直连方式接入 ROS 系统
-
《ROS 2多协议传输控制器》使用 micro-ROS 协议+USB直连方式接入 ROS 系统
开始前准备:
硬件:
- 传输控制板*1
- Type-B电源线*1
- 9~28V电源
软件:
- 安装Ubuntu的系统*1
- 安装好ROS2 Humble以上版本ROS系统
1. micro-ROS Agent 和 消息接口下载与构建
在主目录下创建,ros2_transmission_ws 目录及子目录src(其他目录也可以)
mkdir -p ~/ros2_transmission_ws/src
下载源码
cd ~/ros2_transmission_ws/src git clone http://github.fishros.org/https://github.com/fishros/micro-ROS-Agent -b humble git clone http://github.fishros.org/https://github.com/fishros/robot_interfaces git clone http://github.fishros.org/https://github.com/micro-ROS/micro_ros_msgs.git -b humble
构建工作空间
cd ~/ros2_transmission_ws/ colcon build --- Starting >>> micro_ros_agent Starting >>> robot_interfaces Finished <<< robot_interfaces [6.76s] [Processing: micro_ros_agent] --- stderr: micro_ros_agent 正克隆到 'xrceagent'... 切换到一个新分支 'ros2' HEAD 目前位于 c25243c Enable Domain Override on Reference and XML Participant (#351) CMake Warning (dev) at /usr/share/cmake-3.22/Modules/FindPackageHandleStandardArgs.cmake:438 (message): The package name passed to `find_package_handle_standard_args` (tinyxml2) does not match the name of the calling package (TinyXML2). This can lead to problems in calling code that expects `find_package` result variables (e.g., `_FOUND`) to follow a certain pattern. Call Stack (most recent call first): cmake/modules/FindTinyXML2.cmake:40 (find_package_handle_standard_args) /opt/ros/humble/share/fastrtps/cmake/fastrtps-config.cmake:51 (find_package) CMakeLists.txt:153 (find_package) This warning is for project developers. Use -Wno-dev to suppress it. --- Finished <<< micro_ros_agent [56.9s] Summary: 2 packages finished [58.9s] 1 package had stderr output: micro_ros_agent
看到:Summary: 2 packages finished [58.9s] 就表示构建成功了,中间的警告请忽略。
2.完成硬件连接
这种连接方式的特点是,通过网线将雷达和电脑(控制卡)直连,优点是稳定。
连接方式:
电脑<----Type-B|USB线----->控制板USB口
电源---->控制板电源口3.使用配置助手修改配置
打开配置助手,扫描配置,确认如下选项的值,若不是,请手动修改。
配置项 描述 设置值 transport_mode 传输模式(例如以太网静态IP配置协议) usb usb_baudrate USB传输速率 921600 传输模式我们这里采用 USB ,波特率设置为921600。
设置完成后请手动或者点击配置助手的重启设备进行重启。
5.运行agent,接收消息
进入到工作空间,运行agent, 其中 /dev/ttyUSB0 为设备端口号。
cd ~/ros2_transmission_ws/ source install/setup.bash ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 -b 921600 -v4 --- [1719816514.214416] info | TermiosAgentLinux.cpp | init | running... | fd: 3 [1719816514.214582] info | Root.cpp | set_verbose_level | logger setup | verbose_level: 4 [1719816514.297154] info | Root.cpp | create_client | create | client_key: 0x0F1F6D30, session_id: 0x81 [1719816514.297189] info | SessionManager.hpp | establish_session | session established | client_key: 0x0F1F6D30, address: 0 [1719816514.309030] info | ProxyClient.cpp | create_participant | participant created | client_key: 0x0F1F6D30, participant_id: 0x000(1) [1719816514.313794] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x0F1F6D30, topic_id: 0x000(2), participant_id: 0x000(1) [1719816514.317249] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x0F1F6D30, publisher_id: 0x000(3), participant_id: 0x000(1) [1719816514.320991] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x0F1F6D30, datawriter_id: 0x000(5), publisher_id: 0x000(3) [1719816514.325487] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x0F1F6D30, topic_id: 0x001(2), participant_id: 0x000(1) [1719816514.329048] info | ProxyClient.cpp | create_subscriber | subscriber created | client_key: 0x0F1F6D30, subscriber_id: 0x000(4), participant_id: 0x000(1) [1719816514.332779] info | ProxyClient.cpp | create_datareader | datareader created | client_key: 0x0F1F6D30, datareader_id: 0x000(6), subscriber_id: 0x000(4) [1719816514.337931] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x0F1F6D30, topic_id: 0x002(2), participant_id: 0x000(1) [1719816514.341453] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x0F1F6D30, publisher_id: 0x001(3), participant_id: 0x000(1) [1719816514.345227] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x0F1F6D30, datawriter_id: 0x001(5), publisher_id: 0x001(3) [1719816514.349723] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x0F1F6D30, topic_id: 0x003(2), participant_id: 0x000(1) [1719816514.353673] info | ProxyClient.cpp | create_subscriber | subscriber created | client_key: 0x0F1F6D30, subscriber_id: 0x001(4), participant_id: 0x000(1) [1719816514.357576] info | ProxyClient.cpp | create_datareader | datareader created | client_key: 0x0F1F6D30, datareader_id: 0x001(6), subscriber_id: 0x001(4) [1719816514.362722] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x0F1F6D30, topic_id: 0x004(2), participant_id: 0x000(1) [1719816514.366402] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x0F1F6D30, publisher_id: 0x002(3), participant_id: 0x000(1) [1719816514.370373] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x0F1F6D30, datawriter_id: 0x002(5), publisher_id: 0x002(3) [1719816514.375325] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x0F1F6D30, topic_id: 0x005(2), participant_id: 0x000(1) [1719816514.379148] info | ProxyClient.cpp | create_subscriber | subscriber created | client_key: 0x0F1F6D30, subscriber_id: 0x002(4), participant_id: 0x000(1) [1719816514.382870] info | ProxyClient.cpp | create_datareader | datareader created | client_key: 0x0F1F6D30, datareader_id: 0x002(6), subscriber_id: 0x002(4)
看到上面的日志就表示连接成功了,接着就可以尝试订阅IO状态话题,打开新的终端,输入如下命令:
cd ~/ros2_transmission_ws/ source install/setup.bash ros2 topic echo /read_io --- analog: [] digital: - 1 - 1 - 1 - 1 --- analog: [] digital: - 1 - 1 - 1 - 1 --- ...
可以看到这里每帧输出了四个数据,是四个输入IO的状态,这个话题默认以10Hz进行发布,发布频率可以修改。
使用 ros2 topic list 可以查看控制器节点可以支持的话题。
话题名称 消息接口 订阅/发布 /write_485
robot_interfaces/msg/RawUInt8
订阅 /write_can
robot_interfaces/msg/CanFrame
订阅 /write_io
robot_interfaces/msg/WriteIO
订阅 /read_485
robot_interfaces/msg/RawUInt8
发布 /read_can
robot_interfaces/msg/CanFrame
发布 /read_io
robot_interfaces/msg/ReadIO
发布 关于每个话题如何使用,可以参考例程篇介绍。
6. 设置固定USB端口
-
编写udev规则:
创建一个新的udev规则文件。通常,这些文件位于/etc/udev/rules.d/
目录下。使用root用户或具有sudo权限的用户,在该目录下创建一个新的规则文件,例如99-usb-serial.rules
:sudo nano /etc/udev/rules.d/99-usb-serial.rules
然后在文件中添加以下规则:
SUBSYSTEM=="tty", ATTRS{idVendor}=="1a86", ATTRS{idProduct}=="7523", SYMLINK+="ttyUSBROS2Board"
这个规则指定当
SUBSYSTEM
是tty
,ATTRS{idVendor}
是1a86
,且ATTRS{idProduct}
是7523
时,udev应该创建一个名为ttyUSBROS2Board
的符号链接。 -
重新加载udev规则:
在添加或修改了udev规则之后,需要重新加载udev规则,并触发事件来重新处理当前连接的设备:sudo udevadm control --reload-rules sudo udevadm trigger
或者,您可以简单地重启系统来使更改生效。
-
检查设备节点:
现在,当您的USB设备连接到计算机时,您应该可以在/dev/
目录下看到一个名为ttyUSBROS2Board
的符号链接。您可以使用ls -l /dev/ttyUSBROS2Board
来检查它是否指向了正确的设备节点(例如/dev/ttyUSB0
、/dev/ttyUSB1
等)。
-