一、引言

  1. 上一节中已经构建了一个可以动的机械臂模型,但是没有夹爪并不可以去执行后续的抓取动作
  2. 这一节主要是添加机械臂的夹具到已有的模型上
  3. 因为前面已经做好了铺垫,这里就可以简述一下,然后再进一步说下moveit配置带有夹具的机械臂的过程,其实整体过程都是一样的
  4. 机械手主要由两个joint和三个link(有一个手部还有两个爪子)

二、构建机械手

这一部分同样是用solidworks构建模型然后导出URDF文件,再将机械手和机械臂部分的URDF文件联合在一起~,solikworks这部分不详细说了,附一张我自己的机械手的图片(就直接附gazebo环境的了,懒得切到solidworks中去截图了),然后讲一下导出的思路:

  • (1)基准轴为hand(因为手类似圆柱体啥的)的中心轴
  • (2)将机械手的hand部分视为baselink,两个爪子视为子link后按照以前的步骤直接导出
  • (3)设置axis的时候注意要看下两个爪子的坐标系,别到时候移动方向搞反了(当然反了也没事儿到时候可以很容易修正)

三、使用Setup Assistant配置

emmm和上一节步骤相同的部分我就不说了,主要说加了哪些内容

  • Planning Groups:添加规划组~~
    在这一部分,除去添加arm组还要添加机械组,配置步骤和上一节arm组类似:
  • (1)点击Add Group
    其中Group name为hand,其他不用填都是默认就行
  • (2)点击Add Links和Add Joints按钮,分别将机械手部分的link和joint都添加进组,添加完之后应该和下图一致,一共两个组arm和hand
    (这里我讲的比较简略,看过上一节的同志们应该能意会,不懂就可以评论区问一起讨论)

  • Robot Poses:机器人位姿~~
    这一步和arm配置也是相同的,就是给定一个预设好的位姿,可以让夹具动起来,我这里是设定了一个open和一个close,如下两张图

  • End Effectors:标记末端执行器~~
    这部分比较简单,点击 Add End Effector;End Effector Name为hand;End Effector Group为hand;Parent Link选择arm组的最后一个link即可;Parent Group不选;save之后效果如下图:

  • ROS Control:ROS控制~~
    这一部分也是和上一节配置一模一样,就是配置的时候记得把hand组配置一下,否则rviz里面动的话gazebo里面不会有反应~,hand组的配置,什么type啊啥的都是和arm是一样的,唯一不同的就是joint

最后就是Simulation里面的URDF模型记得按照上一节说的方法来配置修改一下,这里我放一下我的URDF配置文件可以和上一节做一下对比作为参考:

<?xml version="1.0" encoding="utf-8" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from /home/lixushi/catkin_ws/src/kuka_kr16_support/urdf/kr16_2.xacro | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<!--Generates a urdf from the macro in kr16_2_macro.xacro -->
<robot name="kuka_kr16_2">
    <!-- LINKS -->
    <link name="world" />
    <joint name="fixed" type="fixed">
        <parent link="world" />
        <child link="base_link" />
    </joint>
    <!-- base link -->
    <link name="base_link">
        <!--

<inertial>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <mass value="2"/>
        <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
      </inertial>

-->
        <visual>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/base_link.dae" />
            </geometry>
        </visual>
        <collision>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/base_link.stl" />
            </geometry>
        </collision>
        
<inertial>
            <mass value="0.1" />
            <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" />
        </inertial>

    </link>
    <!-- link 1 (A1) -->
    <link name="link_1">
        
<inertial>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <mass value="2" />
            <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
        </inertial>

        <visual>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_1.dae" />
            </geometry>
        </visual>
        <collision>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_1.stl" />
            </geometry>
        </collision>
    </link>
    <!-- link 2 -->
    <link name="link_2">
        
<inertial>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <mass value="2" />
            <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
        </inertial>

        <visual>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_2.dae" />
            </geometry>
        </visual>
        <collision>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_2.stl" />
            </geometry>
        </collision>
    </link>
    <!-- link 3 -->
    <link name="link_3">
        
<inertial>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <mass value="2" />
            <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
        </inertial>

        <visual>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_3.dae" />
            </geometry>
        </visual>
        <collision>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_3.stl" />
            </geometry>
        </collision>
    </link>
    <!-- link 4 -->
    <link name="link_4">
        
<inertial>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <mass value="2" />
            <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
        </inertial>

        <visual>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_4.dae" />
            </geometry>
        </visual>
        <collision>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_4.stl" />
            </geometry>
        </collision>
    </link>
    <!-- link 5 -->
    <link name="link_5">
        
<inertial>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <mass value="2" />
            <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
        </inertial>

        <visual>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_5.dae" />
            </geometry>
        </visual>
        <collision>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_5.stl" />
            </geometry>
        </collision>
    </link>
    <!-- link 6 -->
    <link name="link_6">
        
<inertial>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <mass value="2" />
            <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
        </inertial>

        <visual>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_6.dae" />
            </geometry>
        </visual>
        <collision>
            <origin rpy="0 0 0" xyz="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_6.stl" />
            </geometry>
        </collision>
    </link>
    <!-- tool 0 -->
    <!-- Following REP199, this frame shall be use to attach EEF or other equipment -->
    <link name="gripper_hand_link">
        
<inertial>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <mass value="0.2" />
            <inertia ixx="0.00104990441414208" ixy="1.73103347827347E-06" ixz="0.000406411470197638" iyy="0.00154592185110089" iyz="1.54198397719502E-06" izz="0.0010367313568135" />
        </inertial>

        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/flange.STL" />
            </geometry>
            <material name="">
                <color rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
            </material>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/flange.STL" />
            </geometry>
        </collision>
    </link>
    <!-- END LINKS -->
    <!-- gripper 1 -->
    <link name="gripper_finger_link1">
        
<inertial>
            <origin xyz="0.0055228 0.019773 -0.012596" rpy="0 0 0" />
            <mass value="0.013566" />
            <inertia ixx="3.7098E-06" ixy="-2.2783E-07" ixz="2.3471E-07" iyy="1.2941E-06" iyz="7.9159E-07" izz="3.1381E-06" />
        </inertial>

        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/gripper_finger_link1.STL" />
            </geometry>
            <material name="">
                <color rgba="1 1 1 1" />
            </material>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/gripper_finger_link1.STL" />
            </geometry>
        </collision>
    </link>
    <!-- gripper 2 -->
    <link name="gripper_finger_link2">
        
<inertial>
            <origin xyz="0.0055228 0.019773 -0.012596" rpy="0 0 0" />
            <mass value="0.013566" />
            <inertia ixx="3.7098E-06" ixy="-2.2783E-07" ixz="2.3471E-07" iyy="1.2941E-06" iyz="7.9159E-07" izz="3.1381E-06" />
        </inertial>

        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/gripper_finger_link2.STL" />
            </geometry>
            <material name="">
                <color rgba="1 1 1 1" />
            </material>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/gripper_finger_link2.STL" />
            </geometry>
        </collision>
    </link>
    <!-- JOINTS -->
    <!-- joint 1 (A1) -->
    <joint name="joint_a1" type="revolute">
        <origin rpy="0 0 0" xyz="0 0 0.675" />
        <parent link="base_link" />
        <child link="link_1" />
        <axis xyz="0 0 -1" />
        <limit effort="500" lower="-3.22885911619" upper="3.22885911619" velocity="2.72271363311" />
    </joint>
    <!-- joint 2 (A2) -->
    <joint name="joint_a2" type="revolute">
        <origin rpy="0 0 0" xyz="0.26 0 0" />
        <parent link="link_1" />
        <child link="link_2" />
        <axis xyz="0 1 0" />
        <limit effort="500" lower="-2.70526034059" upper="0.610865238198" velocity="2.72271363311" />
    </joint>
    <!-- joint 3 (A3) -->
    <joint name="joint_a3" type="revolute">
        <origin rpy="0 0 0" xyz="0.68 0 0" />
        <parent link="link_2" />
        <child link="link_3" />
        <axis xyz="0 1 0" />
        <limit effort="500" lower="-2.26892802759" upper="2.68780704807" velocity="2.72271363311" />
    </joint>
    <!-- joint 4 (A4) -->
    <joint name="joint_a4" type="revolute">
        <origin rpy="0 0 0" xyz="0.67 0 -0.035" />
        <parent link="link_3" />
        <child link="link_4" />
        <axis xyz="-1 0 0" />
        <limit effort="500" lower="-6.10865238198" upper="6.10865238198" velocity="5.75958653158" />
    </joint>
    <!-- joint 5 (A5) -->
    <joint name="joint_a5" type="revolute">
        <origin rpy="0 0 0" xyz="0 0 0" />
        <parent link="link_4" />
        <child link="link_5" />
        <axis xyz="0 1 0" />
        <limit effort="500" lower="-2.26892802759" upper="2.26892802759" velocity="5.75958653158" />
    </joint>
    <!-- joint 6 (A6) -->
    <joint name="joint_a6" type="revolute">
        <origin rpy="0 0 0" xyz="0 0 0" />
        <parent link="link_5" />
        <child link="link_6" />
        <axis xyz="-1 0 0" />
        <limit effort="500" lower="-6.10865238198" upper="6.10865238198" velocity="10.7337748998" />
    </joint>
    <!-- hand joint -->
    <joint name="gripper_hand_joint" type="fixed">
        <origin rpy="0 0 -0.7854" xyz="0.965 1.38 0" />
        <parent link="link_6" />
        <child link="gripper_hand_link" />
        <axis xyz="-1 0 0" />
        <limit effort="500" lower="-6.10865238198" upper="6.10865238198" velocity="10.7337748998" />
    </joint>
    <!-- tool frame - fixed frame 
    <joint name="joint_a6-flange" type="fixed">
        <parent link="link_6" />
        <child link="flange" />
        <origin rpy="0 0 0" xyz="0 0 0" />
    </joint>-->
    <!-- gripper joint1 -->
    <joint name="finger_joint1" type="prismatic">
        <origin xyz="0.50069 -1.4539 0.01635" rpy="0 0 -0.7854" />
        <parent link="gripper_hand_link" />
        <child link="gripper_finger_link1" />
        <axis xyz="1 0 0" />
        <limit lower="0" upper="0.025" effort="50" velocity="0.01" />
    </joint>
    <!-- gripper joint2 -->
    <joint name="finger_joint2" type="prismatic">
        <origin xyz="0.49758 -1.4539 -0.01635" rpy="-3.1416 0 2.3562" />
        <parent link="gripper_hand_link" />
        <child link="gripper_finger_link2" />
        <axis xyz="1 0 0" />
        <limit lower="0" upper="0.025" effort="50" velocity="0.01" />
    </joint>
    <!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers 
    <link name="tool0" />
    <joint name="flange-tool0" type="fixed">
        <parent link="flange" />
        <child link="tool0" />
        <origin rpy="0 1.57079632679 0" xyz="0 0 0" />
    </joint>-->
    
<transmission name="trans_joint_a1">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="joint_a1">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="joint_a1_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <transmission name="trans_joint_a2">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="joint_a2">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="joint_a2_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <transmission name="trans_joint_a3">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="joint_a3">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="joint_a3_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <transmission name="trans_joint_a4">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="joint_a4">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="joint_a4_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <transmission name="trans_joint_a5">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="joint_a5">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="joint_a5_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <transmission name="trans_joint_a6">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="joint_a6">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="joint_a6_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <transmission name="trans_finger_joint1">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="finger_joint1">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="finger_joint1_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <transmission name="trans_finger_joint2">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="finger_joint2">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="finger_joint2_motor">
            <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
    <gazebo>
        <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
            <robotNamespace>/</robotNamespace>
        </plugin>
    </gazebo>
</robot>

四、遇到的一些问题及解决

(1)机械臂夹爪位置出现偏移
主要是因为机械臂的坐标系和夹爪坐标系不统一所导致的,可以通过调整机械臂和机械手之间连接的joint中的origin参数来慢慢调试~

  • 调试的时候可以先运行这条指令:
roslaunch gazebo_ros empty_world.launch paused:=true use_sim_time:=false gui:=true throttled:=false recording:=false debug:=true

  • 再运行下面这条指令(别忘了替换成自己的urdf的模型的路径),就可以看到相应的机械臂模型加载在gazebo世界中,然后根据自己情况慢慢调整就可以了
rosrun gazebo_ros spawn_model -file /home/lixushi/Desktop/test.urdf -urdf -x 0 -y 0 -z 0 -model kuka_kr16_2


(2)机械手抖动或者不能回归原位
这里需要修改下夹爪的joint中的effor参数和最大限位

(3)ros_controllers.yaml文件
这个文件的controller_list:需要添加机械手部分的参数,如下


完整的参数配置文件也附在下面,供大家参考

# Simulation settings for using moveit_sim_controllers
moveit_sim_hw_interface:
  joint_model_group: hand
  joint_model_group_pose: open
# Settings for ros_control_boilerplate control loop
generic_hw_control_loop:
  loop_hz: 300
  cycle_time_error_threshold: 0.01
# Settings for ros_control hardware interface
hardware_interface:
  joints:
    - joint_a1
    - joint_a2
    - joint_a3
    - joint_a4
    - joint_a5
    - joint_a6
    - finger_joint1
    - finger_joint2
  sim_control_mode: 1  # 0: position, 1: velocity
# Publish all joint states
# Creates the /joint_states topic necessary in ROS
joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50
controller_list:
  - name: arm_joint_controller
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    default: true
    joints:
      - joint_a1
      - joint_a2
      - joint_a3
      - joint_a4
      - joint_a5
      - joint_a6
  - name: hand_joint_controller
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    default: true
    joints:
      - finger_joint1
      - finger_joint2

arm_joint_controller:
  type: position_controllers/JointTrajectoryController
  joints:
    - joint_a1
    - joint_a2
    - joint_a3
    - joint_a4
    - joint_a5
    - joint_a6
  gains:
    joint_a1:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    joint_a2:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    joint_a3:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    joint_a4:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    joint_a5:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    joint_a6:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
hand_joint_controller:
  type: position_controllers/JointTrajectoryController
  joints:
    - finger_joint1
    - finger_joint2
  gains:
    finger_joint1:
      p: 100
      d: 1
      i: 1
      i_clamp: 1
    finger_joint2:
      p: 100
      d: 1
      i: 1
      i_clamp: 1

五、总结

所以经过以上过程我们已经有一个完整的机械臂模型可以使用并可以后期用C++或者Python的API控制机械臂的移动,来进行物体的抓取等操作~ ,后续会继续更新~