Moveit +Gazebo:搭建单臂机械臂仿真平台

这篇具有很好参考价值的文章主要介绍了Moveit +Gazebo:搭建单臂机械臂仿真平台。希望对大家有所帮助。如果存在错误或未考虑完全的地方,请大家不吝赐教,您也可以点击"举报违法"按钮提交疑问。

环境:Ubuntu20.04 ros-noetic

先放上效果展示:
Moveit +Gazebo:搭建单臂机械臂仿真平台

 Moveit +Gazebo:搭建单臂机械臂仿真平台

 首先要先安装ROS 和 Moveit,ROS的安装就不说了,Moeit的安装参看官网教程

Getting Started — moveit_tutorials Noetic documentation

安装过程中,用到了命令:

rosdep update

最好在安装的时候能够科学上网

搭建单臂仿真平台主要分为4大步

        1.准备urdf/xacro文件

        2.通过moveit setup assistant进行配置

        3.controller的配置

        4.launch文件的编写

准备urdf/xacro文件

这里我采用了 panda机械臂的功能包,首先进行该功能包的安装,通过命令:

sudo apt install ros-noetic-franka-description

        安装好之后呢就可以在目录/opt/ros/noetic/share/franka_description下找到要用的panda机械臂模型的xacro相关文件,这里在进行第二步之前呢,还需要对panda机械臂的xacro文件进行一点点修改,修改的目的主要是使模型具有gazebo仿真的相关标签和数据,这里可以直接使用我修改完成的。(需要安装franka-description包)

建议在moveit的工作空间下,新建一个功能包放置相关文件,比如

我在 moveit_ws/src下新建了panda_dual_arms的功能包,在panda_dual_arms/robot_description下放置了下面的模型文件left_arm.urdf

<?xml version="1.0" ?>
<robot name="left_arm">
  <link name="world"/>
  <joint name="left_base_to_world" type="fixed">
    <parent link="world"/>
    <child link="left_base"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
  </joint>
  <link name="left_base"/>
  <joint name="left_arm_joint_base" type="fixed">
    <parent link="left_base"/>
    <child link="left_arm_link0"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link0">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link0.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link0.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.041018 -0.00014 0.049974"/>
      <mass value="0.629769"/>
      <inertia ixx="0.00315" ixy="8.2904e-07" ixz="0.00015" iyy="0.00388" iyz="8.2299e-06" izz="0.004285"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link0_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link0_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_link0"/>
    <child link="left_arm_link0_sc"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link1">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link1.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link1.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0.003875 0.002081 -0.04762"/>
      <mass value="4.970684"/>
      <inertia ixx="0.70337" ixy="-0.000139" ixz="0.006772" iyy="0.70661" iyz="0.019169" izz="0.009117"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link1_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link1_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_link1"/>
    <child link="left_arm_link1_sc"/>
  </joint>
  <joint name="left_arm_joint1" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0.333"/>
    <parent link="left_arm_link0"/>
    <child link="left_arm_link1"/>
    <axis xyz="0 0 1"/>
    <limit effort="87.0" lower="-2.8973" upper="2.8973" velocity="2.175"/>
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link2">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link2.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link2.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.003141 -0.02872  0.003495"/>
      <mass value="0.646926"/>
      <inertia ixx="0.007962" ixy="-0.003925" ixz="0.010254" iyy="0.02811" iyz="0.000704" izz="0.025995"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link2_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link2_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_link2"/>
    <child link="left_arm_link2_sc"/>
  </joint>
  <joint name="left_arm_joint2" type="revolute">
    <origin rpy="-1.5707963267948966 0 0" xyz="0 0 0"/>
    <parent link="left_arm_link1"/>
    <child link="left_arm_link2"/>
    <axis xyz="0 0 1"/>
    <limit effort="87.0" lower="-1.7628" upper="1.7628" velocity="2.175"/>
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628"/>
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link3">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link3.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link3.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="2.7518e-02 3.9252e-02 -6.6502e-02"/>
      <mass value="3.228604"/>
      <inertia ixx="0.037242" ixy="-0.004761" ixz="-0.011396" iyy="0.036155" iyz="-0.012805" izz="0.01083"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link3_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link3_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_link3"/>
    <child link="left_arm_link3_sc"/>
  </joint>
  <joint name="left_arm_joint3" type="revolute">
    <origin rpy="1.5707963267948966 0 0" xyz="0 -0.316 0"/>
    <parent link="left_arm_link2"/>
    <child link="left_arm_link3"/>
    <axis xyz="0 0 1"/>
    <limit effort="87.0" lower="-2.8973" upper="2.8973" velocity="2.175"/>
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link4">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link4.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link4.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-5.317e-02 1.04419e-01 2.7454e-02"/>
      <mass value="3.587895"/>
      <inertia ixx="0.025853" ixy="0.007796" ixz="-0.001332" iyy="0.019552" iyz="0.008641" izz="0.028323"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link4_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link4_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_link4"/>
    <child link="left_arm_link4_sc"/>
  </joint>
  <joint name="left_arm_joint4" type="revolute">
    <origin rpy="1.5707963267948966 0 0" xyz="0.0825 0 0"/>
    <parent link="left_arm_link3"/>
    <child link="left_arm_link4"/>
    <axis xyz="0 0 1"/>
    <limit effort="87.0" lower="-3.0718" upper="-0.0698" velocity="2.175"/>
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/>
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link5">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link5.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link5.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-1.1953e-02 4.1065e-02 -3.8437e-02"/>
      <mass value="1.225946"/>
      <inertia ixx="0.035549" ixy="-0.002117" ixz="-0.004037" iyy="0.029474" iyz="0.000229" izz="0.008627"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link5_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link5_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_link5"/>
    <child link="left_arm_link5_sc"/>
  </joint>
  <joint name="left_arm_joint5" type="revolute">
    <origin rpy="-1.5707963267948966 0 0" xyz="-0.0825 0.384 0"/>
    <parent link="left_arm_link4"/>
    <child link="left_arm_link5"/>
    <axis xyz="0 0 1"/>
    <limit effort="12.0" lower="-2.8973" upper="2.8973" velocity="2.61"/>
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link6">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link6.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link6.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="6.0149e-02 -1.4117e-02 -1.0517e-02"/>
      <mass value="1.666555"/>
      <inertia ixx="0.001964" ixy="0.000109" ixz="-0.001158" iyy="0.004354" iyz="0.000341" izz="0.005433"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link6_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link6_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_link6"/>
    <child link="left_arm_link6_sc"/>
  </joint>
  <joint name="left_arm_joint6" type="revolute">
    <origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
    <parent link="left_arm_link5"/>
    <child link="left_arm_link6"/>
    <axis xyz="0 0 1"/>
    <limit effort="12.0" lower="-0.0175" upper="3.7525" velocity="2.61"/>
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525"/>
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_link7">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/link7.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/link7.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="1.0517e-02 -4.252e-03 6.1597e-02"/>
      <mass value="0.735522"/>
      <inertia ixx="0.012516" ixy="-0.000428" ixz="-0.001196" iyy="0.010027" iyz="-0.000741" izz="0.004815"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_link7_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_link7_sc_joint" type="fixed">
    <origin rpy="0 0 0.7853981633974483"/>
    <parent link="left_arm_link7"/>
    <child link="left_arm_link7_sc"/>
  </joint>
  <joint name="left_arm_joint7" type="revolute">
    <origin rpy="1.5707963267948966 0 0" xyz="0.088 0 0"/>
    <parent link="left_arm_link6"/>
    <child link="left_arm_link7"/>
    <axis xyz="0 0 1"/>
    <limit effort="12.0" lower="-2.8973" upper="2.8973" velocity="2.61"/>
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
  </joint>
  <link name="left_arm_link8"/>
  <joint name="left_arm_joint8" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0.107"/>
    <parent link="left_arm_link7"/>
    <child link="left_arm_link8"/>
  </joint>
  <joint name="left_arm_hand_joint" type="fixed">
    <parent link="left_arm_link8"/>
    <child link="left_arm_hand"/>
    <origin rpy="0 0 -0.7853981633974483" xyz="0 0 0"/>
  </joint>
  <!-- sub-link defining detailed meshes for collision with environment -->
  <link name="left_arm_hand">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/hand.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://franka_description/meshes/collision/hand.stl"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.01 0 0.03"/>
      <mass value="0.73"/>
      <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.0025" iyz="0" izz="0.0017"/>
    </inertial>
  </link>
  <!-- sub-link defining coarse geometries of real robot's internal self-collision -->
  <link name="left_arm_hand_sc">
  </link>
  <!-- fixed joint between both sub-links -->
  <joint name="left_arm_hand_sc_joint" type="fixed">
    <origin rpy="0 0 0"/>
    <parent link="left_arm_hand"/>
    <child link="left_arm_hand_sc"/>
  </joint>
  <!-- Define the hand_tcp frame -->
  <link name="left_arm_hand_tcp"/>
  <joint name="left_arm_hand_tcp_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0.1034"/>
    <parent link="left_arm_hand"/>
    <child link="left_arm_hand_tcp"/>
  </joint>
  <link name="left_arm_leftfinger">
    <visual>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/finger.dae"/>
      </geometry>
    </visual>
    <!-- screw mount -->
    <collision>
      <origin rpy="0 0 0" xyz="0 18.5e-3 11e-3"/>
      <geometry>
        <box size="22e-3 15e-3 20e-3"/>
      </geometry>
    </collision>
    <!-- cartriage sledge -->
    <collision>
      <origin rpy="0 0 0" xyz="0 6.8e-3 2.2e-3"/>
      <geometry>
        <box size="22e-3 8.8e-3 3.8e-3"/>
      </geometry>
    </collision>
    <!-- diagonal finger -->
    <collision>
      <origin rpy="0.5235987755982988 0 0" xyz="0 15.9e-3 28.35e-3"/>
      <geometry>
        <box size="17.5e-3 7e-3 23.5e-3"/>
      </geometry>
    </collision>
    <!-- rubber tip with which to grasp -->
    <collision>
      <origin rpy="0 0 0" xyz="0 7.58e-3 45.25e-3"/>
      <geometry>
        <box size="17.5e-3 15.2e-3 18.5e-3"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.015"/>
      <inertia ixx="2.3749999999999997e-06" ixy="0" ixz="0" iyy="2.3749999999999997e-06" iyz="0" izz="7.5e-07"/>
    </inertial>
  </link>
  <link name="left_arm_rightfinger">
    <visual>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://franka_description/meshes/visual/finger.dae"/>
      </geometry>
    </visual>
    <!-- screw mount -->
    <collision>
      <origin rpy="0 0 0" xyz="0 -18.5e-3 11e-3"/>
      <geometry>
        <box size="22e-3 15e-3 20e-3"/>
      </geometry>
    </collision>
    <!-- cartriage sledge -->
    <collision>
      <origin rpy="0 0 0" xyz="0 -6.8e-3 2.2e-3"/>
      <geometry>
        <box size="22e-3 8.8e-3 3.8e-3"/>
      </geometry>
    </collision>
    <!-- diagonal finger -->
    <collision>
      <origin rpy="-0.5235987755982988 0 0" xyz="0 -15.9e-3 28.35e-3"/>
      <geometry>
        <box size="17.5e-3 7e-3 23.5e-3"/>
      </geometry>
    </collision>
    <!-- rubber tip with which to grasp -->
    <collision>
      <origin rpy="0 0 0" xyz="0 -7.58e-3 45.25e-3"/>
      <geometry>
        <box size="17.5e-3 15.2e-3 18.5e-3"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.015"/>
      <inertia ixx="2.3749999999999997e-06" ixy="0" ixz="0" iyy="2.3749999999999997e-06" iyz="0" izz="7.5e-07"/>
    </inertial>
  </link>
  <joint name="left_arm_finger_joint1" type="prismatic">
    <parent link="left_arm_hand"/>
    <child link="left_arm_leftfinger"/>
    <origin rpy="0 0 0" xyz="0 0 0.0584"/>
    <axis xyz="0 1 0"/>
    <limit effort="100" lower="0.0" upper="0.04" velocity="0.2"/>
    <dynamics damping="0.3"/>
  </joint>
  <joint name="left_arm_finger_joint2" type="prismatic">
    <parent link="left_arm_hand"/>
    <child link="left_arm_rightfinger"/>
    <origin rpy="0 0 0" xyz="0 0 0.0584"/>
    <axis xyz="0 -1 0"/>
    <limit effort="100" lower="0.0" upper="0.04" velocity="0.2"/>
    <mimic joint="left_arm_finger_joint1"/>
    <dynamics damping="0.3"/>
  </joint>

  <gazebo reference="left_arm_joint1">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_joint1_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_joint1">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_joint1_motor">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  <gazebo reference="left_arm_joint2">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_joint2_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_joint2">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_joint2_motor">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  <gazebo reference="left_arm_joint3">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_joint3_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_joint3">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_joint3_motor">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  <gazebo reference="left_arm_joint4">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_joint4_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_joint4">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_joint4_motor">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  <gazebo reference="left_arm_joint5">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_joint5_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_joint5">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_joint5_motor">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  <gazebo reference="left_arm_joint6">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_joint6_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_joint6">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_joint6_motor">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  <gazebo reference="left_arm_joint7">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_joint7_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_joint7">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_joint7_motor">
      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </actuator>
  </transmission>


  <gazebo reference="left_arm_finger_joint1">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_finger_joint1_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_finger_joint1">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_finger_joint1_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  <gazebo reference="left_arm_finger_joint2">
    <!-- Needed for ODE to output external wrenches on joints -->
    <provideFeedback>true</provideFeedback>
  </gazebo>
  <transmission name="left_arm_finger_joint2_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="left_arm_finger_joint2">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="left_arm_finger_joint2_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </actuator>
  </transmission>

  <!-- load ros_control plugin -->
  <gazebo>
    <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control"/>
      <robotNamespace>/left_arm</robotNamespace>
  </gazebo>
</robot>

Moveit setup assitant的配置

详细的配置介绍和过程参考官方教程:MoveIt Setup Assistant — moveit_tutorials Noetic documentation

        这里我贴上我的配置过程,进行了自碰撞矩阵、规划组、姿态、末端执行器的配置,关于虚拟关节和被动关节以及控制器的环节跳过即可。

自碰撞矩阵,按照默认情况生成即可

Moveit +Gazebo:搭建单臂机械臂仿真平台

规划组分为arm和hand 两个组,arm组名我这里是:left_arm添加如图下所示的joint,hand是:left_hand,添加如图下所示的links

Moveit +Gazebo:搭建单臂机械臂仿真平台

这里我还配置了几个pose,主要方便后期的编程,各个pose包含的关节值:

ready:{0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785}.

open:0.035

close:0.0

Moveit +Gazebo:搭建单臂机械臂仿真平台

 最后就是定义的末端执行器

Moveit +Gazebo:搭建单臂机械臂仿真平台

 完成后会得到一个 我命名为 left_arm_moveit_config的功能包

在工作空间下重新 catkin build 并 source

通过命令 roslaunch left_arm_moveit_config demo.launch能够运行,并且能够通过rviz对及机械臂进行规划则没有问题。

controller的配置

首先是joint_state_controller,主要作用是发布机器人的关节状态和TF变换

在panda_dual_arms/config 下创建 joint_state_controller.yaml

joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50

然后是trajectory_controller,Moveit完成运动规划后输出接口是一个命名为FollowJointTrajectory的action,其中包含一系列规划好的路径点轨迹,Trajectory Controller的作用就是将这些信息转化成Gzebo中机器人需要输入的joint位置。

在panda_dual_arms/config trajectory_controller.yaml

left_arm_trajectory_controller:
    type: "position_controllers/JointTrajectoryController"
    joints:
        - left_arm_joint1
        - left_arm_joint2
        - left_arm_joint3
        - left_arm_joint4
        - left_arm_joint5
        - left_arm_joint6
        - left_arm_joint7
    constraints:
        goal_time: 0.6
        stopped_velocity_tolerance: 0.05
        left_arm_joint1: {trajectory: 0.1, goal: 0.1}
        left_arm_joint2: {trajectory: 0.1, goal: 0.1}
        left_arm_joint3: {trajectory: 0.1, goal: 0.1}
        left_arm_joint4: {trajectory: 0.1, goal: 0.1}
        left_arm_joint5: {trajectory: 0.1, goal: 0.1}
        left_arm_joint6: {trajectory: 0.1, goal: 0.1}
        left_arm_joint7: {trajectory: 0.1, goal: 0.1}
    stop_trajectory_duration: 0.5
    state_publish_rate:  25
    action_monitor_rate: 10

#notice that the grippers joint2 mimics joint1
#this is why it is not listed under the hand controllers

left_hand_controller:
    type: "effort_controllers/JointTrajectoryController"
    joints:
        - left_arm_finger_joint1
    gains:
        left_arm_finger_joint1:  {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}

launch文件的编写

launch文件的个部分内容都有注释,主要就是启动gazebo,启动moveit,启动上面的controller,启动rviz

<?xml version="1.0"?>
<launch>
        <!-- Run the main MoveIt executable with trajectory execution -->
        <include file="$(find left_arm_moveit_config)/launch/move_group.launch">
            <arg name="allow_trajectory_execution" value="true" />
            <arg name="moveit_controller_manager" value="ros_control" />
            <arg name="fake_execution_type" value="interpolate" />
            <arg name="info" value="true" />
            <arg name="debug" value="false" />
            <arg name="pipeline" value="ompl" />
            <arg name="load_robot_description" value="true" />
        </include>

    <!-- Launch empty Gazebo world -->
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="use_sim_time" value="true" />
        <arg name="gui" value="true" />
        <arg name="paused" value="false" />
        <arg name="debug" value="false" />
    </include>

        <param name="robot_description" command="$(find xacro)/xacro  '$(find panda_dual_arms)/robot_description/left_arm.urdf'" />
        <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -param robot_description -model left_arm" />

        <!-- Robot state publisher -->
        <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
            <param name="publish_frequency" type="double" value="50.0" />
            <param name="tf_prefix" type="string" value="" />
        </node>
        <!-- Joint state controller -->
        <rosparam file="$(find panda_dual_arms)/config/left_arm_joint_state_controller.yaml" command="load" />
        <node name="joint_state_controller_spawner" pkg="controller_manager" type="spawner"  args="joint_state_controller" respawn="false" output="screen" />

        <!-- Joint trajectory controller -->
        <rosparam file="$(find panda_dual_arms)/config/left_arm_trajectory_controller.yaml" command="load" />
        <node name="arms_trajectory_controller_spawner" pkg="controller_manager" type="spawner"  respawn="false" output="screen"  args="left_arm_trajectory_controller left_hand_controller" />
    
        <!-- Start moveit_rviz with the motion planning plugin -->
        <include file="$(find left_arm_moveit_config)/launch/moveit_rviz.launch">
            <arg name="rviz_config" value="$(find left_arm_moveit_config)/launch/moveit.rviz" />
        </include>
</launch>

参考:Multiple Robot Arms — moveit_tutorials Noetic documentation文章来源地址https://www.toymoban.com/news/detail-505060.html

到了这里,关于Moveit +Gazebo:搭建单臂机械臂仿真平台的文章就介绍完了。如果您还想了解更多内容,请在右上角搜索TOY模板网以前的文章或继续浏览下面的相关文章,希望大家以后多多支持TOY模板网!

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处: 如若内容造成侵权/违法违规/事实不符,请点击违法举报进行投诉反馈,一经查实,立即删除!

领支付宝红包 赞助服务器费用

相关文章

  • 我终于实现Moveit+gazbeo对机械臂的联合仿真控制了

          开发机械臂,别的问题都好商量,但是对于实体机械臂这个烧钱的东西来说,绝对是一大批开发者的拦路虎。方法总比困难多。对于没有实体机械臂只能进行仿真的人来说,gazebo可真是太香了。但是浏览了一众网上的的教程,一步一步跟着走了无数遍,最终面临的问题

    2024年01月18日
    浏览(32)
  • 【ROS&GAZEBO】多旋翼无人机仿真(一)——搭建仿真环境

    【ROSGAZEBO】多旋翼无人机仿真(一)——搭建仿真环境 【ROSGAZEBO】多旋翼无人机仿真(二)——基于rotors的仿真 【ROSGAZEBO】多旋翼无人机仿真(三)——自定义无人机模型 【ROSGAZEBO】多旋翼无人机仿真(四)——探索控制器原理 【ROSGAZEBO】多旋翼无人机仿真(五)——位置

    2023年04月17日
    浏览(46)
  • ROS自学笔记二十: Gazebo里面仿真环境搭建

    Gazebo 中创建仿真实现方式有两种:1直接添加内置组件创建仿真环境2: 手动绘制仿真环境 添加完毕后,选择 file --- Save World as 选择保存路径(功能包下: worlds 目录),文件名自定义,后缀名设置为 .world 点击: 左上角 file --- Save (保存路径功能包下的: models) 然后 file --- Exit Building

    2024年02月06日
    浏览(29)
  • 11.机器人系统仿真搭建gazebo环境、仿真深度相机、雷达、RGB相机

    目录 1 gazebo仿真环境搭建 1.1  直接添加内置组件创建仿真环境 1.2 urdf、gazebo、rviz的综合应用 2 ROS_control 2.1 运动控制实现流程(Gazebo) 2.1.1 已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加传动装置以及控制器 2.1.2 将此文件集成进xacro文件 2.1.3 修改

    2024年02月04日
    浏览(41)
  • ROS学习第三十六节——Gazebo仿真环境搭建

    1.1加入环境模型 在工程文件中创建worlds文件夹,并把之前下载的box_house.world文件放入  1.2编写launch文件 deamo03_car_world.launch 2.1启动 Gazebo 并添加组件 2.2保存仿真环境 添加完毕后,选择 file --- Save World as 选择保存路径(功能包下: worlds 目录),文件名自定义,后缀名设置为 .worl

    2023年04月24日
    浏览(28)
  • 【ROS2机器人入门到实战】Gazebo仿真环境搭建

    当前平台文章汇总地址:ROS2机器人从入门到实战 获取完整教程及配套资料代码,请关注公众号鱼香ROS获取 教程配套机器人开发平台:两驱版| 四驱版 为方便交流,搭建了机器人技术问答社区:地址 fishros.org.cn 本节我们要在Gazebo中建立一个测试的环境,其实也很简单,利用

    2024年02月05日
    浏览(44)
  • Gazebo——仿真平台搭建(基于Ubuntu20.04) 1.gazebo--SpawnModel: Failure - model name mrobot already exists.

    目录 Gazebo安装配置 创建仿真环境  仿真使用 Rviz查看摄像头采集的信息 Kinect仿真 问题解决: 1.gazebo--SpawnModel: Failure - model name mrobot already exists. 1.设置你的电脑来接收软件 2.设置秘钥 3.安装Gazebo 4.检查你的安装是否有效果= 5.打开 /.gazebo文件夹 下载模型 如果出现fatal连接GitH

    2023年04月19日
    浏览(76)
  • 从零开始的机械臂yolov5抓取gazebo仿真(四)

    上一篇博客已经将moveit!配置完毕,然而想要让moveit!控制gazebo中的机械臂,还需要进行一些接口的配置。现在我们有的功能包为sunday_description、sunday_moveit_config这两个功能包。且已经配置好xacro文件,本篇内容需要进行gazebo功能包的配置以及moveit功能包的文件修改。 创建sunda

    2023年04月24日
    浏览(29)
  • 从零开始的机械臂yolov5抓取gazebo仿真(二)

    上一节中拿到了sunday_description功能包,将功能包放进工作空间进行编译,可将工作空间路径写进.bashrc文件中,这样就不必每次都source了 编译通过后,修改sunday_description/launch/display.launch文件将 arg name=\\\"gui\\\" default=\\\"False\\\" / 改为 arg name=\\\"gui\\\" default=\\\"Ture\\\" / ,运行launch文件 可以看到机械

    2023年04月08日
    浏览(29)
  • 从零开始的机械臂yolov5抓取gazebo仿真(三)

    在开篇博主先说一下博主使用的moveit_setup_assistant用的ubuntu16.04+ros_kinetic版本配置的,因为使用相同的方法在melodic中配置,无论如何也不能与gazebo联动,各位可以装个虚拟机在kinetic中配置完再拿到melodic中使用,或者在20.04环境中配置。 开头介绍一下博主踩过的坑,接下去介绍

    2024年02月11日
    浏览(26)

觉得文章有用就打赏一下文章作者

支付宝扫一扫打赏

博客赞助

微信扫一扫打赏

请作者喝杯咖啡吧~博客赞助

支付宝扫一扫领取红包,优惠每天领

二维码1

领取红包

二维码2

领红包