构建可移动机器人模型

目标:学习如何在 URDF 中定义可移动关节。

教程级别:中级

时间:10 分钟

在本教程中,我们将修改在 上一个教程 中创建的 R2D2 模型,使其具有可移动的关节。 在上一个模型中,所有关节都是固定的。 现在我们将探索其他三种重要的关节类型:连续关节、旋转关节和棱柱关节。

在本教程中,我们将修改在 上一个教程 中创建的 R2D2 模型,使其具有可移动的关节。 在上一个模型中,所有关节都是固定的。 现在我们将探索其他三种重要的关节类型:连续关节、旋转关节和棱柱关节。

ros2 launch urdf_tutorial display.launch.py model:=urdf/06-flexible.urdf

但是现在这也会弹出一个 GUI,允许您控制所有非固定关节的值。 玩一下模型,看看它是如何移动的。 然后,我们可以看看我们是如何实现这一点的。

Screenshot of Flexible Model

The Head

<joint name="head_swivel" type="continuous">
  <parent link="base_link"/>
  <child link="head"/>
  <axis xyz="0 0 1"/>
  <origin xyz="0 0 0.3"/>
</joint>

身体和头部之间的连接是一个连续关节,这意味着它可以呈现从负无穷到正无穷的任何角度。 轮子也是这样建模的,这样它们就可以永远向两个方向滚动。

我们唯一需要添加的附加信息是旋转轴,这里由 xyz 三元组指定,它指定头部将围绕其旋转的向量。 因为我们希望它绕着 z 轴旋转,所以我们指定向量“0 0 1”。

夹钳

<joint name="left_gripper_joint" type="revolute">
  <axis xyz="0 0 1"/>
  <limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
  <origin rpy="0 0 0" xyz="0.2 0.01 0"/>
  <parent link="gripper_pole"/>
  <child link="left_gripper"/>
</joint>

左右夹持关节均被建模为旋转关节。 这意味着它们以与连续关节相同的方式旋转,但它们有严格的限制。 因此,我们必须包含限制标签,指定关节的上限和下限(以弧度为单位)。 我们还必须为该关节指定最大速度和力,但实际值对于我们的目的而言并不重要。

夹持臂

<joint name="gripper_extension" type="prismatic">
  <parent link="base_link"/>
  <child link="gripper_pole"/>
  <limit effort="1000.0" lower="-0.38" upper="0" velocity="0.5"/>
  <origin rpy="0 0 0" xyz="0.19 0 0.2"/>
</joint>

夹臂是一种不同类型的关节,即棱柱关节。 这意味着它沿轴移动,而不是绕轴移动。 这种平移运动使我们的机器人模型能够伸展和缩回其夹臂。 棱柱臂的极限与旋转关节的指定方式相同,只是单位是米,而不是弧度。

其他类型的关节

还有两种在空间中移动的关节。 棱柱关节只能沿一个维度移动,而平面关节可以在平面或两个维度上移动。 此外,浮动关节不受约束,可以在三个维度中的任何一个维度上移动。 这些关节不能仅用一个数字指定,因此不包含在本教程中。

指定姿势

当您在 GUI 中移动滑块时,模型会在 Rviz 中移动。 这是如何做到的?首先,GUI 解析 URDF 并找到所有非固定关节及其限值。 然后,它使用滑块的值发布 sensor_msgs/msg/JointState 消息。 然后,robot_state_publisher 使用这些消息来计算不同部分之间的所有变换。 然后使用生成的变换树在 Rviz 中显示所有形状。

下一步

现在您有一个可见的功能模型,您可以:doc:添加一些物理属性,或:doc:开始使用 xacro 简化您的代码