系列文章目录
【附带源码】机械臂MoveIt2极简教程(一)、moveit2安装
【附带源码】机械臂MoveIt2极简教程(二)、move_group交互
【附带源码】机械臂MoveIt2极简教程(三)、URDF/SRDF介绍
【附带源码】机械臂MoveIt2极简教程(四)、第一个入门demo
【附带源码】机械臂MoveIt2极简教程(五)、第二个demo - rviz可视化
目录
在移动机器人中,一般只需要URDF(Unified Robot Description Format)模型描述文件就够了,但是在机械臂操作中,仅仅一个URDF不够,还需要SRDF(Semantic Robot Description Format)。你可以把URDF理解成乐高里面的积木和说明书,有了它,你就可以搭出一个机器人。而SRDF则更像详细说明书。
1. URDF
MoveIt2从URDF中导入一个机械臂,URDF是ROS1\ROS2通用的机器人模型描述格式。
1.1 URDF相关资源
URDF ROS 维基百科:网址链接
URDF教程:网址链接
solidworks URDF插件:网址链接 你可以通过solidworks导出一个URDF的机器人模型。
1.2 小技巧
下面有几个注意事项,确保你生成的URDF手册能够在moveit2中使用。
1.2.1 关节名称
关节名称不应该包含特殊字符 -,[,],(,),
1.2.2 安全限制
机器人关节限位。机械臂的每个关节并不是都能做360°旋转的,就像人的关节一样。因此必须在URDF手册里写明每个关节所对应的限制条件。
举个例子:
<safety_controller k_position="100" k_velocity="1.5" soft_lower_limit="-2.857" soft_upper_limit="2.857"/>
soft_lower_limit
和soft_upper_limit
描述了该关节的关节位置限制。moveit2将会把这两个参数和hard limits
进行对比,选择最保守的值来运行机器人模型。
soft_lower_limit和soft_upper_limit如果是0.0,那么该关节无法旋转移动了。所以每个参数要设置的很合理。
1.2.3 碰撞检测
MoveIt2使用网格来进行碰撞检测。(就是我们常说的栅格地图中的栅格)
URDF允许可视化和碰撞检测的栅格分开设置。通常来说,可视化栅格会更加具体,也更好看,但是碰撞栅格就会简单一点。当检测机械臂连杆是否碰撞时,网格中三角形的数量影响碰撞检测的耗时。一般整个机器人的三角形数量控制在几千个左右。
1.2.4 测试URDF
ROS的URDF包提供了check_urdf工具,可以用来检测你写的URDF文件是否正确。
sudo apt install liburdfdom-tools
check_urdf pr2.urdf
打印信息如下:
robot name is: pr2
---------- Successfully Parsed XML ---------------
root Link: base_footprint has 1 child(ren)
child(1): base_link
child(1): base_laser_link
child(2): bl_caster_rotation_link
child(1): bl_caster_l_wheel_link
child(2): bl_caster_r_wheel_link
child(3): br_caster_rotation_link
child(1): br_caster_l_wheel_link
child(2): br_caster_r_wheel_link
child(4): fl_caster_rotation_link
child(1): fl_caster_l_wheel_link
child(2): fl_caster_r_wheel_link
child(5): fr_caster_rotation_link
child(1): fr_caster_l_wheel_link
child(2): fr_caster_r_wheel_link
child(6): torso_lift_link
child(1): head_pan_link
child(1): head_tilt_link
child(1): head_plate_frame
child(1): sensor_mount_link
child(1): double_stereo_link
child(1): narrow_stereo_link
也可以可视化输出
urdf_to_graphiz pr2.urdf
会输出有个pdf文件,列出了所有模型信息。
1.3 URDF例子
在ROS社区,有很多的URDF例子可以让你去学习和参考:网址
pr2机器人:适配ros melodic和noetic版本
2. SRDF
SRDF详细配置了关节组,包括默认的机器人配置、碰撞检测信息、机器人位姿变换等。推荐的生成SRDF方式是利用MoveIt Setup Assistant。
2.1 虚拟关节
URDF只描述了机器人的物理关节。但是虚拟关节也是需要的。因为在世界坐标系中,常常要定义机器人连杆之间的位姿变换。对于移动机器人,比如pr2机器人,会有一个灵活可变的虚拟关节连接着机器人和世界坐标;对于固定工业机械臂,会有一个固定虚拟关节连接机械臂和世界坐标。
其实就是world到base_link的关系。
2.2 被动关节
被动关节就是机器人中非驱动的关节。比如移动机器人里面除了差分驱动轮连接的关节以外,都是被动关节。被动关节是在SRDF里面单独设置的,确保他们在运动规划和控制流程中无法被直接控制。
2.3 组
MoveIt2中有一个核心概念:Group(组)。有时叫关节组,或者规划组。组包含多个关节和连杆的集合。
所有的运动规划与控制都是以组作为基本单元进行控制。
2.3.1 关节组
一系列关节组成的组。
每个关节的child link都默认包含在组中。
2.3.2 连杆组
一系列连杆组成的组。
这些连杆的parent joint也会包含在组中。
记忆:一个joint和它的子link是一个整体。
2.3.3 Serial Chain
serial chain是由base_link和tip link以及中间多个关节、连杆组成。头是base_link,尾巴是tip link。
2.3.4 组的集合
组和组之间也可以进行集合,形成更大的组。
2.4 末端执行器
机器人中的某些特定组叫末端执行器。它一般是通过固定关节连接到手臂上。
2.5 自碰撞
默认的自碰撞矩阵生成器会搜索机器人link坐标系上其他的成对links,目的是为了防止碰撞检测,降低运动规划处理时间。当这些成对的links处在碰撞中、未发生碰撞、在默认位置碰撞、相邻连杆条件下,是无法使能的。采样密度规定了检测自碰撞时需要有多少个机器人位姿。高采样密度会耗算力;低采样密度可能会造成关节有更大可能性被禁用。默认值是10000个碰撞检测。
2.6 机器人姿态
SRDF存储了机器人的固定配置。配置都会自带一个字符串类型的id用以区分。id也会被用来恢复配置。
2.7 SRDF文件说明
通用的文件格式如下:
<?xml version="1.0"?>
<!-- This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined -->
<robot name="some robot">
<group name="group1">
<!-- when a link is specified, the parent joint of that link (if it exists) is automatically included -->
<link name="..."/>
<link name="..."/>
<!-- when a joint is specified, the child link of that joint (which will always exist) is automatically included -->
<joint name="..." />
<!-- when a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group -->
<chain base_link="l_shoulder_pan_link" tip_link="l_wrist_roll_link"/>
<chain base_link="r_shoulder_pan_link" tip_link="r_wrist_roll_link"/>
</group>
<!-- groups can also be formed by referencing to already defined group names -->
<group name="arms">
<group name="left_arm"/>
<group name="right_arm"/>
<link name="..." />
</group>
<!-- define a named state/configuration of a group -->
<group_state name="name of this state" group="name of group the state is for">
<joint name="name of joint in group" value="" />
<!-- all joints must be specified for the state to be valid -->
</group_state>
<!-- Define how the robot moves in its environment, i.e., connection to robot's root link -->
<virtual_joint name="world_joint" type="planar" parent_frame="some fixed frame" child_link="robot's root link name"/> <!-- type can be planar, floating or fixed -->
<!-- We can then include the virtual joint in groups -->
<group name="whole_body">
<group name="arms"/>
<joint name="world_joint"/>
</group>
<!-- define end effectors -->
<end_effector name="some diff name" parent_link="..." group="group_name"/>
<!-- By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. There can be many such tags in this file.-->
<disable_collisions link1="link1" link2="link2" />
</robot>
pr2的SRDF如下:
<?xml version="1.0"?>
<robot name="pr2">
<virtual_joint name="world_joint" type="planar" parent_frame="odom" child_link="base_footprint"/>
<group name="right_arm">
<chain base_link="torso_lift_link" tip_link="r_wrist_roll_link"/>
</group>
<group name="left_arm">
<chain base_link="torso_lift_link" tip_link="l_wrist_roll_link"/>
</group>
<group name="arms">
<group name="left_arm"/>
<group name="right_arm"/>
</group>
<group_state name="tuck_arms" group="arms">
<joint name="l_shoulder_pan_joint" value="0.2" />
<!-- ... the rest of the joint values... -->
</group_state>
<group name="base">
<joint name="world_joint"/>
</group>
<group name="whole_body">
<group name="arms"/>
<group name="base"/>
<joint name="torso_lift_joint"/>
</group>
<group name="l_end_effector">
<joint name="l_gripper_palm_joint" />
<joint name="l_gripper_l_finger_joint" />
<joint name="l_gripper_l_finger_tip_joint" />
<joint name="l_gripper_led_joint" />
<joint name="l_gripper_motor_accelerometer_joint" />
<joint name="l_gripper_motor_slider_joint" />
<joint name="l_gripper_motor_screw_joint" />
<joint name="l_gripper_r_finger_joint" />
<joint name="l_gripper_r_finger_tip_joint" />
<joint name="l_gripper_joint" />
<joint name="l_gripper_tool_joint" />
</group>
<group name="r_end_effector">
<joint name="r_gripper_palm_joint" />
<joint name="r_gripper_l_finger_joint" />
<joint name="r_gripper_l_finger_tip_joint" />
<joint name="r_gripper_led_joint" />
<joint name="r_gripper_motor_accelerometer_joint" />
<joint name="r_gripper_motor_slider_joint" />
<joint name="r_gripper_motor_screw_joint" />
<joint name="r_gripper_r_finger_joint" />
<joint name="r_gripper_r_finger_tip_joint" />
<joint name="r_gripper_joint" />
<joint name="r_gripper_tool_joint" />
</group>
<end_effector name="r_end_effector" parent_link="r_wrist_roll_link" group="r_end_effector"/>
<end_effector name="l_end_effector" parent_link="l_wrist_roll_link" group="l_end_effector"/>
<disable_collisions link1="r_shoulder_pan_link" link2="r_shoulder_lift_link" />
<!-- and many more disable_collisions tags -->
</robot>
3. 加载URDF和SRDF
加载这两个文件通常用xacro,具体如下
from launch_ros.parameter_descriptions import ParameterValue
from launch.substitutions import Command
robot_description = ParameterValue(Command(['xacro ', PATH_TO_URDF]), value_type=str)
同时,SRDF必须详细地读取
with open(PATH_TO_SRDF, 'r') as f:
semantic_content = f.read()
读取到的每个值也要在node节点中加载
move_group_node = Node(package='moveit_ros_move_group', executable='move_group',
output='screen',
parameters=[{
'robot_description': robot_description,
'robot_description_semantic': semantic_content,
# More params
}],
)
机器人描述信息的发布则是通过Robot State Publisher
节点,发布的topic是/robot_description
,消息类型是std_msgs/msg/String
。
觉得对您有帮助的,可以点个赞👍支持一下,谢谢各位!
因为淋过雨,所以想为别人撑把伞;因为踩过太多坑,所以想让喜欢机器人的同学们减少试错成本!