MoveIt Grasps

../../../_images/moveit_grasps.png

MoveIt Grasps 是用于抓取块或圆柱体等物体的抓取生成器,可用作 MoveIt 拾取和放置管道的替代品。MoveIt Grasps 提供基于可达性和接近、提升和后退运动的笛卡尔规划来过滤抓取的功能。

抓取生成算法基于简单的长方体形状,不考虑摩擦锥或其他抓取动力学。

MoveIt Grasps 可与平行手指夹持器和吸盘夹持器一起使用。

入门

如果您尚未完成,请确保您已完成以下步骤 Getting Started.

安装 MoveIt Grasps

从源代码安装

克隆 moveit_grasps 存储库 catkin workspace. 在本教程中,我们使用 Franka Emika 的熊猫机器人设置 panda_moveit_config:

cd ~/ws_moveit/src
git clone -b $ROS_DISTRO-devel https://github.com/moveit/moveit_grasps.git

使用rosdep工具自动安装其依赖项::

rosdep install –from-paths . –ignore-src –rosdistro $ROS_DISTRO

构建工作区::

catkin build

从 Debian 安装

Note: 截至 2019 年 4 月 11 日,此软件包尚未发布:

sudo apt-get install ros-$ROS_DISTRO-moveit-grasps

演示脚本

我们提供了 4 个演示脚本来展示 MoveIt Grasps,并用于可视化 MoveIt Grasps 配置参数。

在运行任何演示之前,您必须先使用以下命令启动 Rviz:

roslaunch moveit_grasps rviz.launch

默认设置使用双指夹持器。 要使用吸盘夹持器运行演示,请在启动 Rviz 时指定夹持器:

roslaunch moveit_grasps rviz.launch gripper:=suction

NOTE: 已发布的版本 panda_moveit_config 可能落后于源版本。如果您对演示版本有疑问,第一步是下载并构建 panda_moveit_config 来自来源。

1) 整个 MoveIt 抓取管道

要查看整个 MoveIt Grasps 管道的运行情况,请运行:

roslaunch moveit_grasps grasp_pipeline_demo.launch

../../../_images/grasp_pipeline_demo.gif

2) 可视化夹持器参数

要可视化夹持器特定参数:

roslaunch moveit_grasps grasp_poses_visualizer_demo.launch

结果看起来应该是这样的:

../../../_images/moveit_grasps_poses.jpg

3) 可视化抓握生成

此工具演示了抓握生成过程中评分如何进行的几个概念。 它使用以下方法确定所选的抓握方式:

  • Ideal TCP Grasp Pose: the generator will bias the chosen grasp based on an input of a preferred grasp. This allows you to say, for example, ‘I want the end-effector to be pointed down left when grasping the object’.

  • Pose-Based Grasp Score Weighting: Bias certain translation or rotation axes to score higher, by increasing the weight of that specific axis.

  • Depth-Based Grasp Score Weighting: Bias a deeper grasp depth (how enveloped the fingers are around the object) over other parameters

  • Width-Based Grasp Score Weighting: (For parallel finger grippers only) Bias a wider finger grasp (how much space is available between the object and the finger pads) over other parameters

  • Overhang Grasp Score Weighting: (For suction grippers only) Bias a suction grasp towards full overlap with the object. This scoring metric uses the square of the percent of the suction region that is in contact with the object. By using the square, suction grippers with multiple suction regions (voxels) bias towards solutions with 100% overlap with one voxel rather than 50% of one and 50% of another.

可视化:

roslaunch moveit_grasps grasp_generator_demo.launch

../../../_images/grasp_generator_demo.png

4) 掌握过滤器

演示掌握过滤::

roslaunch moveit_grasps grasp_filter_demo.launch

经过过滤后,颜色代表以下内容:

  • 红色 - 通过 ik 过滤的抓握

  • 粉色 - 通过碰撞过滤的抓握

  • 洋红色 - 通过切割平面过滤的抓握

  • 黄色 - 通过方向过滤的抓握

  • 蓝色 - 通过 ik 过滤的预抓握

  • 青色 - 通过碰撞过滤的预抓握

  • 绿色 - 有效

5) 吸盘抓取管道

要演示使用吸盘抓取器的管道,请运行:

roslaunch moveit_grasps suction_grasp_pipeline_demo.launch

概念概述

MoveIt Grasps 基于三个主要组件:

  • Grasp Generator uses the end effector kinematic and the object shape for sampling grasp poses and optimizing them using geometric scoring functions.

  • Grasp Filter validates the feasibility of grasp candidates by searching for IK solutions to verify their reachability.

  • Grasp Planner computes Cartesian approach, lift, and retreat trajectories that compose a complete grasp motion.

注意:理想情况下,Grasp Planner 最终将被淘汰,取而代之的是新的 MoveIt Task Constructor

为了运行完整的掌握管道,需要按顺序应用三个组件。

此外,Grasp Generator 使用以下组件:

  • Grasp Scorer 在已知问题/应用信息的情况下,支持多种启发式方法,用于判断哪些抓取是有利的

在文件内可以找到生成、过滤和规划抓握动作的示例 src/grasp_pipeline_demo.cpp. Instructions for running are below.

机器人无关的配置

MoveIt Grasps 需要在启动时指定两个配置文件:

  • ROBOT_grasp_data.yaml describes the robot’s end effector geometry and is custom for each robot

  • moveit_grasps_config.yaml configures the behavior of Grasp Generator, Grasp Filter and Grasp Planner. Additionally, it contains many optional debugging and visualizations options to make usage of MoveIt Grasps far easier.

除了本教程之外,请参阅以下示例文件中的注释以获取有关参数的进一步解释:

ROBOT_grasp_data.yaml

典型示例末端执行器配置使用了 Franka Emika 的 Panda: config_robot/panda_grasp_data.yaml.

在该文件中,您将找到使用吸盘或手指夹持器定制 MoveIt Grasps 所需的所有夹持器特定参数。

ROBOT_grasp_data.yaml 文件中参数的示意图

  1. Finger gripper parameters

../../../_images/finger_gripper_explanation.jpg
  1. Suction gripper parameters

../../../_images/suction_gripper_explanation.jpg

* 这些变量可以直接在*ROBOT_grasp_data.yaml*文件中配置。

** 您可以通过设置 ROBOT_grasp_data.yaml 文件中的 tcp_name 变量来配置工具中心点链接的名称。

moveit_grasps_config.yaml

可以在以下位置找到 Grasp GeneratorGrasp FilterGrasp Planner 的示例配置文件 config/moveit_grasps_config.yaml.

应用与机器人无关的配置

要应用您的 yaml 配置,请将其作为 rosparams 加载到您的抓取应用程序/ROS 节点中。 有关示例,请参阅文件中的以下片段 launch/grasp_pipeline_demo.launch:

<node name="moveit_grasps_demo" pkg="moveit_grasps" type="moveit_grasps_pipeline_demo">
  <param name="ee_group_name" value="hand"/>
  <param name="planning_group_name" value="panda_arm"/>
  <rosparam command="load" file="$(find moveit_grasps)/config_robot/panda_grasp_data.yaml"/>
  <rosparam command="load" file="$(find moveit_grasps)/config/moveit_grasps_config.yaml"/>
</node>

请注意,必须在两个 yaml 文件中指定机器人的规划组和末端执行器组,在参数下 ee_group_name and planning_group_name.

由于参数设置相当广泛,因此您可以使用不同的演示启动文件来可视化效果。您可以将配置应用于本教程后面描述的演示启动文件。

其他配置说明

tcp_to_eef_mount_transform

The tcp_to_eef_mount_transform 表示从用于抓取姿势的工具中心点到末端执行器的安装链接的变换。 提供此参数是为了允许不同的 URDF 末端执行器协同工作而无需重新编译代码。

在 MoveIt 中,驱动的末端执行器手指应始终具有父链接,通常是腕部链接或手掌链接。 此腕部链接应使其手掌的 Z 轴指向您想要抓取的物体,即您的食指指向的位置。

这是 John Craig 于 1955 年在《机器人学》中提出的惯例。 然而,许多 URDF 并不遵循这个惯例,因此这种转换可以让你修复它。

此外,x 轴应该沿着抓握的物体指向上方,即如果你握着啤酒瓶的话,x 轴就是啤酒瓶的圆轴。

y 轴应该指向其中一个手指。

Switch from Bin to Shelf Picking

The setIdealGraspPoseRPY() and setIdealGraspPose() GraspGenerator 中的方法可用于选择理想的抓取方向。

这些方法用于对抓取候选者进行评分,以偏向更接近所需方向的抓取。

这在诸如箱子和货架挑选等应用中非常有用,在这些应用中,您可能希望从箱子中拾取垂直对齐的抓取对象,也可能希望从货架中拾取水平对齐的抓取对象。

经过测试的机器人

  • UR5

  • Jaco2

  • Baxter

  • REEM

  • Panda