Skip to content

添加末端执行器

一、构建末端执行器URDF

在机器人描述包里,新建文件: gripper.xacro

xml
<?xml version="1.0"?>
<robot name="temp" xmlns:xacro="http://www.ros.org/wiki/xacro"> 

    <material name="dark_green">
        <color rgba="0 0.4 0 1.0"/>
    </material>

    <material name="light_green">
        <color rgba="0 0.6 0 1.0"/>
    </material>

    <link name="gripper_base_link">
        <visual>
            <geometry>
                <box size="0.2 0.06 0.02"/>
            </geometry>
            <origin rpy="0 0 0.01" xyz="0 0 0"/>
            <material name="dark_green"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.2 0.06 0.02"/>
            </geometry>
            <origin rpy="0 0 0.01" xyz="0 0 0"/>
        </collision>        
    </link>
    <link name="gripper_left_finger_link">
        <visual>
            <geometry>
                <box size="0.02 0.06 0.08"/>
            </geometry>
            <origin rpy="0 0 0.0" xyz="0 0 0.04"/>
            <material name="light_green"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.02 0.06 0.08"/>
            </geometry>
            <origin rpy="0 0 0.0" xyz="0 0 0.04"/>
        </collision>
    </link>
    
    <link name="gripper_right_finger_link">
        <visual>
            <geometry>
                <box size="0.02 0.06 0.08"/>
            </geometry>
            <origin rpy="0 0 0.0" xyz="0 0 0.04"/>
            <material name="light_green"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.02 0.06 0.08"/>
            </geometry>
            <origin rpy="0 0 0.0" xyz="0 0 0.04"/>
        </collision>
    </link>

    <joint name="gripper_left_finger_joint" type="prismatic">
        <parent link="gripper_base_link"/>
        <child link="gripper_left_finger_link"/>
        <origin xyz="-0.07 0.0 0.02" rpy="0.0 0.0 0.0"/>
        <axis xyz="1 0 0"/>
        <limit lower="0.0" upper="0.06" effort="1000" velocity="0.0"/>
    </joint>

    <joint name="gripper_right_finger_joint" type="prismatic">
        <parent link="gripper_base_link"/>
        <child link="gripper_right_finger_link"/>
        <origin xyz="0.07 0.0 0.02" rpy="0.0 0.0 0.0"/>
        <axis xyz="1 0 0"/>
        <mimic joint="gripper_left_finger_joint" multiplier="-1"/>
        <limit lower="-0.06" upper="0" effort="1000" velocity="0.0"/>
    </joint>
</robot>

预览如下:

二、连接执行器到机械臂

修改机械臂主文件robot.urdf.xacro,添加末端执行器绑定:

xml
<?xml version="1.0"?>
<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro"> 

    <xacro:include filename="common_properties.xacro"/>
    <xacro:include filename="arm.xacro"/>
    <xacro:include filename="gripper.xacro"/>

    <joint name="gripper_base_joint" type="fixed">
        <parent link="tool_link"/>
        <child link="gripper_base_link"/>
        <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
    </joint>

</robot>

这里通过将 tool_link 和 gripper_base_link连接 完成末端执行器和机械臂本身的连接。

预览如下:

代码: https://github.com/DuRuofu/moveit2_learn/commit/3cacfdd2af1e41d78979fdf99bbb4c3834fd75b5

三、配置Moveit2

我们启动Moveit2 配置助手(在工作区目录下启动):

ros2 launch moveit_setup_assistant  setup_assistant.launch.py

选择编辑现有配置:

加载上一节生成的配置包,首先重新生成碰撞矩阵:

添加新的规划组:

添加夹爪对应的关节:

最终我们拥有两个规划组,如下。

添加夹爪姿态,我这里的Ui显示有问题,只能添加初始状态(后续在配置文件里手动添加):

定义末端执行器:

点击添加接口:

点击自动添加控制器:

重新生成包:

生成完成后,我们还需要手动修复一些文件:

首先是joint_limits.yaml:

yaml
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed

# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests.  # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1

# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
  gripper_left_finger_joint:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0
  gripper_right_finger_joint:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0
  joint1:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0
  joint2:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0
  joint3:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0
  joint4:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0
  joint5:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0
  joint6:
    has_velocity_limits: true
    max_velocity: 1.0
    has_acceleration_limits: true
    max_acceleration: 1.0

my_robot.srdf里手动添加夹爪位置定义:

xml
    <group_state name="gripper_open" group="gripper">
        <joint name="gripper_left_finger_joint" value="0"/>
    </group_state>
        <group_state name="gripper_closed" group="gripper">
        <joint name="gripper_left_finger_joint" value="0.06"/>
    </group_state>

然后尝试运行demo:

bash
cd ros2_ws 
colcon build
source install/setup.bash
ros2 launch my_robot_moveit_config demo.launch.py

可以正常对夹爪进行运动规划:

关于末端执行器的添加到此为止

代码: https://github.com/DuRuofu/moveit2_learn/commit/388995569c5b80ac8d8b05914b9ad36acff15f7d