零、 前言
这是一个复盘,最近在尝试使用一个ROS Master管理两个独立的UR10e机器人系统,由于我的两个系统都已经配置好各自的moveit了,而且在配置之初并没有考虑有另一个UR,所以所有的控制器、话题、节点、ROS参数名这些都是重复的。
由于系统的缘故,我的moveit本身就很繁杂,常规添加ns参数指定命名空间的方法也不能直接使用,因此我现在梳理一下,尝试从moveit原理的角度再次思考一遍这个过程,防止自己以后忘掉。同时我也借此机会梳理一下自己对Moveit的理解。
如何实现两个机器人各自的局域网不变的基础上,配置桥接和映射完成网络通讯的内容,我准备后面再总结另一个心得,这里就只针对一个ROS Master下如何保证每个机器人有独立的命名空间这件事进行总结。
一、概述
我认为,想把一个机器人的命名空间隔离好,需要分为以下几层改动:
1. 外部控制(UR10e 驱动文件)
表层改动,大概牵扯到 ex-ur10-1.launch、ur_common.launch、ur_control.launch
事实证明,只添加<group ns="robot_A">和 指定 tf_prefix参数,不能解决问题。。。
2. Moveit启动,表层的几个launch
我这里大概跳转10个左右的launch,其实就是Moveit表层各种启动项,但是并不是所有launch都能被ns参数影响到的。各个功能等下我详细说,大概牵扯到:
(1)ur10e_moveit_config/launch/你自己的moveit启动.launch(rviz+moveit之类的)
(2)planning_execution.launch
(3)move_group.launch
(4)planning_context.launch(就是这里启动了你自定义的URDF和SRDF之类的一堆,但是 <group ns="robot_A">的影响力基本到这里就到头了,下边还需后续步骤一一手改。)
3. 我们设备的URDF、SRDF文件
这个是为了moveit启动加载的,但是2中添加的ns无法传入我们的URDF、SRDF
4. robot_description的一些改动
robot_description等坑,这些其实是上位机代码启动Moveit Commander时,需要改的。
5. TF树问题
6. 代码层面的配合改动
二、外部控制(UR10e 驱动文件)改动细节
我这里的启动项是一一跳转的,这里需要改的主要是控制器、话题、节点、ROS参数名这些。
改动1: tf_prefix
tf_prefix
是 ROS 中的一种常见参数,通常用来为机器人在 TF 坐标树(TF tree)中的 frame 名称添加一个前缀。它的主要作用是在多机器人场景中区分每个机器人的 TF 坐标帧,避免命名冲突。
(1)在多机器人环境中,如果两个机器人都有一个 base_link
坐标帧,那么它们的 TF tree 会发生冲突,因为 ROS TF 要求所有帧的名称在整个系统中是唯一的。
(2)通过使用 tf_prefix
,可以为每个机器人加一个前缀,例如 robot_A/base_link
和 robot_B/base_link
,从而避免冲突
这里我添加了,但是不知道为什么,没有传进去,而且我的机器人不止UR的link和joint,还有很多我添加的关节,所以这里我没有成功,而是直接在后面改了,不过这里还是建议先添加上。
改动2:robot_state_publisher
功能:
(1)将机器人 /joint_states
话题中的关节信息转换为 TF 坐标变换,并发布到 /tf
话题中。用于维护机器人在 ROS 中的坐标树结构
(2)将该节点放入 robot_A
命名空间后,所有发布的话题和参数都会加上 robot_A/
前缀,例如:
/joint_states
→ /robot_A/joint_states
/tf
→ /robot_A/tf
遗憾的是,我这里的robot_state_publisher不是个包,我是在opt/ros下的,可以看看自己的路径在哪里。我在这里卡了很久,tf话题根本不会变,导致两台tf树互相冲突,因为opt/ros下是二进制的吧,也没有cpp。这里我甚至还尝试了去重新下载一个有代码的robot_state_publisher,并且手改CPP让ROS Master中出现两个/tf树,但是不应该这样,一个系统应该只有一个tf树。所以我的解决方法在下面。
改动3: ur_hardware_interface、controller_manager的发布
这里主要是要改一些node,改的方法就是把node放在ns参数里面包起来:
<group ns="robot_A">
你想包装的node
</group>
ur_hardware_interface
功能:负责与UR机器人硬件的通信(主要通过RTDE协议),实现数据传输和机器人运动指令控制。
ur_tool_communication_bridge
功能:将机器人工具端口(工具IO、通信接口等)通过 socat
桥接到本地设备(如 /dev/tty
)。
controller_manager 和 controller_stopper
controller_manager
节点功能:用于加载和管理机器人控制器,例如关节状态、速度、力矩等控制器。
controller_stopper
节点功能:确保机器人在停止运行时禁用某些控制器。
ur_robot_state_helper
功能:帮助处理和发布UR机器人状态信息(如是否运行程序等)。
三、Moveit启动,表层的几个launch改动细节
注意,我们一般改moveit都是用Moveit setup assistant,但是这里面是没办法指定命名空间的,因此还是要深入Moveit改动。
改动1:整个moveit的启动launch
这里我就是在最外层启动一下rviz,按道理来说,这里嵌套一个<group ns="robot_A">就能实现改动了,事实确实如此,launch后面索引到的launch,在设置ros参数和节点的时候,都会带上robot_A, 但是远远不够。
Moveit知识1:启动项的跳转
可以看到刚刚这个跳转到ur10e_moveit_planning_execution.launch,这个一般是用于指定要不要有仿真,以及加载并启动 MoveIt! 的核心节点 move_group
,用于实现路径规划、运动控制和碰撞检测。
重映射控制器话题,适配仿真或真实机器人环境。
启动 MoveIt! 的核心节点,为UR10e机器人提供路径规划与运动执行功能。
Moveit知识2:move_group
由于move_group是最重要的一个节点,这里我贴出我的move_group代码,并详细解释以下都加载了什么。
<launch>
<!-- GDB Debug Option -->
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix"
value="gdb -x $(find ur10e_moveit_config)/launch/gdb_settings.gdb --ex run --args" />
<!-- Verbose Mode Option -->
<arg name="info" default="$(arg debug)" />
<arg unless="$(arg info)" name="command_args" value="" />
<arg if="$(arg info)" name="command_args" value="--debug" />
<!-- move_group settings -->
<arg name="pipeline" default="ompl" />
<arg name="allow_trajectory_execution" default="true"/>
<arg name="fake_execution" default="false"/>
<arg name="max_safe_path_cost" default="1"/>
<arg name="jiggle_fraction" default="0.05" />
<arg name="publish_monitored_planning_scene" default="true"/>
<arg name="capabilities" default=""/>
<arg name="disable_capabilities" default=""/>
<!-- load these non-default MoveGroup capabilities (space seperated) -->
<!--
<arg name="capabilities" value="
a_package/AwsomeMotionPlanningCapability
another_package/GraspPlanningPipeline
" />
-->
<!-- inhibit these default MoveGroup capabilities (space seperated) -->
<!--
<arg name="disable_capabilities" value="
move_group/MoveGroupKinematicsService
move_group/ClearOctomapService
" />
-->
<arg name="load_robot_description" default="true" />
<!-- load URDF, SRDF and joint_limits configuration -->
<include file="$(find ur10e_moveit_config)/launch/planning_context2.launch">
<arg name="load_robot_description" value="$(arg load_robot_description)" />
</include>
<!-- Planning Functionality -->
<include ns="move_group" file="$(find ur10e_moveit_config)/launch/planning_pipeline.launch.xml">
<arg name="pipeline" value="$(arg pipeline)" />
</include>
<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(find ur10e_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_manage_controllers" value="true" />
<arg name="moveit_controller_manager" value="ur10e" unless="$(arg fake_execution)"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
</include>
<!-- Sensors Functionality -->
<include ns="move_group" file="$(find ur10e_moveit_config)/launch/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_sensor_manager" value="ur10e" />
</include>
<!-- Start the actual move_group node/action server -->
<node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
<!-- Set the display variable, in case OpenGL code is used internally -->
<env name="DISPLAY" value="$(optenv DISPLAY :0)" />
<param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
<param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
<param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
<param name="capabilities" value="$(arg capabilities)"/>
<param name="disable_capabilities" value="$(arg disable_capabilities)"/>
<!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
<param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
</node>
</launch>
具体的:
move_group节点一般会启动以下内容:
机器人模型加载
从参数服务器中加载机器人描述文件(URDF、SRDF),包括机械臂的几何结构、运动学约束、关节极限等。
定义了机械臂的运动规划组(Planning Group)和默认的末端执行器配置。
规划场景管理器
启动场景管理组件,用于处理机器人与周围环境的交互,包括添加障碍物、虚拟对象、桌面等。
路径规划器
加载OMPL(Open Motion Planning Library)或其他第三方规划器,用于计算从起始状态到目标状态的运动轨迹。
运动学求解器
加载逆运动学求解器(如KDL或IKFast),实现从末端执行器目标位置到关节空间角度的映射。
控制接口
接收用户通过RViz或API(Python/C++)发出的规划请求,并执行规划的轨迹。
通过 follow_joint_trajectory 接口将规划的轨迹下发到机器人控制器。
传感器接口
接收传感器数据(如深度摄像头、激光雷达),实时更新环境模型。
实时反馈与监控
提供路径规划、执行状态的实时反馈。
这里我最关心的还是:
<arg name="load_robot_description" default="true" />
<!-- load URDF, SRDF and joint_limits configuration -->
<include file="$(find ur10e_moveit_config)/launch/planning_context2.launch">
<arg name="load_robot_description" value="$(arg load_robot_description)" />
</include>
因为这个定义了我们的机器人长啥样?(URDF样子+SRDF语义)
Moveit知识3:URDF+SRDF
可以看到就是跳转进了这个launch,启动了URDF和SRDF。这个 launch 文件 是 MoveIt 配置中最核心的部分之一,它负责 加载机器人模型、语义描述文件以及运动学和规划相关的参数,为 MoveIt 的 move_group
节点提供必要的信息。这些内容会被 MoveIt 用于路径规划、碰撞检测、逆运动学求解等操作
加载机器人描述文件(URDF)
(1)如果参数 load_robot_description
为 true
,则通过 xacro
工具加载 ur_socket_complex2.xacro
文件,将其解析为 URDF 格式,并存储到 robot_description
参数下。
(2)作用:提供机械臂的几何信息(关节、连杆、工具中心点等)和惯性属性,用于运动学计算和碰撞检测。
加载语义描述文件(SRDF)
这里有个大坑,就是他们都是由外部控制(UR10e 驱动文件)启动后的robot_description参数来的,如果我们两台机器,就会在这里同时注册SRDF,就会导致控制报错,因为commander不知道该找谁,参数服务器上只允许有一个URDF+SRDF!!!!这就是第五章那里要解决的问题。
(1)将 SRDF 文件加载到参数服务器,存储在 robot_description_semantic
(或其他命名空间)参数下。
- 作用:SRDF 补充了 URDF 中没有的高层信息,比如:
- 禁用的关节或碰撞检查设置。
- 默认的末端执行器。
- 规划组:哪些关节可以一起运动(如
manipulator
组)。 - MoveIt 使用此文件来规划路径和检测碰撞。
四、URDF、SRDF文件改动细节
改动1:SRDF
改动2:URDF
五、robot_description的一些改动
这个是解决上边说的,参数服务器上只允许有一个URDF+SRDF
所以我们必须给每个机器人的robot_description放在各自的命名空间下:
rosparam list看一下,要像这样才行,
但是,上边的‘Moveit知识3:URDF+SRDF’中提到的,moveit启动更多的参数时,是从参数服务器中直接找的,所以我们要一开始启动UR时,就把这个给改了!
需要改的位置如下:
这就是一切的初始,就是先把一个赤裸的UR加载进参数服务器,moveit也只是拿来继续拼接我们的!!!!!!!!!!!!!!!
下面是moveit启动后多的:
六、TF树问题
这个就是上边说的问题了,一个ros master应该只有一个tf和静态tf,但是我这里使用参数tf_prefix不管用。
所以我的思路是,手动改所有的关节、连杆、坐标系:
1. Controller定义中的全部要,改控制器定义
2. UR10e URDF+SRDF
3. 末端URDF
自己的执行器关节也要加,因为要拼起来
4. ur10_moveit_config/config/ros_controllers.yaml
这下,tf就没问题啦。
七、代码层面的配合改动
主要是moveit commander的,我感觉是commander底层的原因,会默认读不带工作空间的话题,所以我们要多添加几个参数直接指定命名空间和参数服务器中他自己的URDF+SRDF:
ns="/robot_A", robot_description="/robot_A/robot_description"
moveit_commander.roscpp_initialize(sys.argv)
group = moveit_commander.MoveGroupCommander("manipulator", ns="/robot_A", robot_description="/robot_A/robot_description")
综上,就全部改好了!