Skip to content
Snippets Groups Projects
panda_arm_hand.urdf.xacro 1.46 KiB
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
  <xacro:include filename="$(find franka_description)/robots/panda_arm.xacro"/>
  <xacro:include filename="$(find franka_description)/robots/hand.xacro"/>

  <!-- for simulation -->
  <xacro:include filename="$(find franka_description)/robots/panda.gazebo.xacro"/>
  <xacro:include filename="panda.transmission.xacro"/>
  <!-- end for simulation -->

  <xacro:panda_arm />
  <xacro:hand ns="panda" rpy="0 0 ${-pi/4}" connected_to="panda_link8"/>

  <!-- for simulation -->
  <xacro:arg name="robot_name" default="panda"/>
  <xacro:panda_gazebo robot_name="$(arg robot_name)" />
  <xacro:panda_transmission robot_name="$(arg robot_name)" load_hand="true" />
  <!-- end for simulation -->

  <gazebo>
    <plugin name="gazebo_grasp_fix" filename="libgazebo_grasp_fix.so">
      <arm>
        <arm_name>panda_arm</arm_name>
        <palm_link> panda_link7  </palm_link>
        <gripper_link> panda_rightfinger </gripper_link>
        <gripper_link> panda_leftfinger </gripper_link>
      </arm>
      <forces_angle_tolerance>100</forces_angle_tolerance>
      <update_rate>4</update_rate>
      <grip_count_threshold>4</grip_count_threshold>
      <max_grip_count>8</max_grip_count>
      <release_tolerance>0.005</release_tolerance>
      <disable_collisions_on_attach>false</disable_collisions_on_attach>
      <contact_topic>__default_topic__</contact_topic>
    </plugin>
  </gazebo>
</robot>