差速驱动移动基座和机械臂的规划

本教程将展示如何配置带有差速驱动基座的移动机械手,以便您可以使用 MoveIt 规划基座和其他自由度的协调运动。虽然您可以使用 MoveIt 仅规划基座,但不建议这样做。使用 Nav2 进行纯导航。请注意,本教程使用 Hello Robot 的 Stretch 平台进行演示,但对于任何带有差速驱动基座的移动机械手,都可以使用相同的方法。

../../../_images/intro.png

入门

如果您尚未完成,请确保您已完成 Getting Started.

安装

安装依赖项:

cd ~/ws_moveit/src
wget https://raw.githubusercontent.com/PickNikRobotics/stretch_ros/ros2/stretch_ros.repos
vcs import < stretch_ros.repos
rosdep install -r --from-paths . --ignore-src --rosdistro rolling -y

构建 colcon 工作区::

cd ~/ws_moveit
colcon build --event-handlers desktop_notification- status- --cmake-args -DCMAKE_BUILD_TYPE=Release

获取 colcon 工作区::

source ~/ws_moveit/install/setup.bash

为移动底座和手臂设置 IK 解算器

要设置运动学插件,我们需要一个由两个关节模型组组成的关节模型组:一个用于机械手,另一个用于移动基座,该基座只有一个平面类型的关节,因此“*.srdf”文件应该具有:

<group name="manipulator">
  ...
</group>
<group name="mobile_base">
  <joint name="planar_joint" /> <!-- planar_joint must have planar type -->
</group>
<group name="mobile_base_manipulator">
  <group name="manipulator" />
  <group name="mobile_base" />
</group>

在“kinematics.yaml”文件中,“mobile_base_manipulator”组需要有“stretch_kinematics_plugin/StretchKinematicsPlugin”作为运动学解算器

mobile_base_manipulator:
  kinematics_solver: stretch_kinematics_plugin/StretchKinematicsPlugin
  kinematics_solver_search_resolution: 0.005
  kinematics_solver_timeout: 0.1

See stretch_description.srdf and kinematics.yaml for how it’s been set-up for stretch robot.

对于源代码,请查看 stretch_kinematics_plugin

设置底座的运动学模型

为了能够生成差速驱动底座的计划,我们需要设置两个关节属性

motion_model

这用于配置平面关节模型,它可以有两个值:

  • holonomic:关节可以向任何方向移动,如果未指定 motion_model 关节属性,则这是默认值

  • diff_drive:关节将具有差分驱动约束(不能侧向移动)

<joint_property joint_name="planar_joint_name" property_name="motion_model" value="diff_drive" />

最小平移距离

如果两个状态之间的距离小于“min_translational_distance”,则运动将是纯旋转,默认值为“1e-5”,有关为什么需要这样做的更多信息,请参阅“computeTurnDriveTurnGeometry <https://github.com/moveit/moveit2/blob/main/moveit_core/robot_model/src/planar_joint_model.cpp#L149>” .. code-block:: xml

<joint_property joint_name=”planar_joint_name” property_name=”min_translational_distance” value=”0.01” />

角度距离权重

可以为平面关节(diff_drive/holonomic)和浮动关节设置,默认值为“1.0”

这用于计算两个基本姿势“(x0,y0,theta0)”和“(x1,y1,theta1)”之间的距离,该距离定义为位置和方向之间距离的加权和:“||(x0,y0)-(x1,y1)|| + angular_distance_weight * |theta0 - theta1|”。

<joint_property joint_name="planar_joint_name" property_name="angular_distance_weight" value="0.5" />

运行代码

打开 shell 并启动 RViz,等待所有内容加载完成::

ros2 launch stretch_moveit_config demo.launch.py use_fake_controller:=True

启动文件

整个启动文件是 here 在 GitHub 上。