<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from config/panda.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="panda">
<link name="world"/>
<joint name="world_to_panda_link" type="fixed">
<parent link="world"/>
<child link="panda_link0"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<link name="panda_link0">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link0.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_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-7" ixz="0.00015" iyy="0.00388" iyz="8.2299E-6" izz="0.004285"/>
</inertial>
</link>
<link name="panda_link1">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link1.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_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>
<joint name="panda_joint1" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="0 0 0" xyz="0 0 0.333"/>
<parent link="panda_link0"/>
<child link="panda_link1"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.3925"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="panda_link2">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link2.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_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="-3.925E-3" ixz="1.0254E-2" iyy="2.811E-2" iyz="7.04E-4" izz="2.5995E-2"/>
</inertial>
</link>
<joint name="panda_joint2" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628"/>
<origin rpy="-1.57079632679 0 0" xyz="0 0 0"/>
<parent link="panda_link1"/>
<child link="panda_link2"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-1.8326" upper="1.8326" velocity="2.3925"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="panda_link3">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link3.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/collision/link3.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="2.7518E-2 3.9252E-2 -6.6502E-2"/>
<mass value="3.228604"/>
<inertia ixx="3.7242E-2" ixy="-4.761E-3" ixz="-1.1396E-2" iyy="3.6155E-2" iyz="-1.2805E-2" izz="1.083E-2"/>
</inertial>
</link>
<joint name="panda_joint3" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="1.57079632679 0 0" xyz="0 -0.316 0"/>
<parent link="panda_link2"/>
<child link="panda_link3"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.3925"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="panda_link4">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link4.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/collision/link4.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-5.317E-2 1.04419E-1 2.7454E-2"/>
<mass value="3.587895"/>
<inertia ixx="2.5853E-2" ixy="7.796E-3" ixz="-1.332E-3" iyy="1.9552E-2" iyz="8.641E-3" izz="2.8323E-2"/>
</inertial>
</link>
<joint name="panda_joint4" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="0.0175"/>
<origin rpy="1.57079632679 0 0" xyz="0.0825 0 0"/>
<parent link="panda_link3"/>
<child link="panda_link4"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-3.1416" upper="0.0873" velocity="2.3925"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="panda_link5">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link5.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/collision/link5.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-1.1953E-2 4.1065E-2 -3.8437E-2"/>
<mass value="1.225946"/>
<inertia ixx="3.5549E-2" ixy="-2.117E-3" ixz="-4.037E-3" iyy="2.9474E-2" iyz="2.29E-4" izz="8.627E-3"/>
</inertial>
</link>
<joint name="panda_joint5" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
<parent link="panda_link4"/>
<child link="panda_link5"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.9671" upper="2.9671" velocity="2.8710"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="panda_link6">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link6.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/collision/link6.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="6.0149E-2 -1.4117E-2 -1.0517E-2"/>
<mass value="1.666555"/>
<inertia ixx="1.964E-3" ixy="1.09E-4" ixz="-1.158E-3" iyy="4.354E-3" iyz="3.41E-4" izz="5.433E-3"/>
</inertial>
</link>
<joint name="panda_joint6" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525"/>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<parent link="panda_link5"/>
<child link="panda_link6"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-0.0873" upper="3.8223" velocity="2.8710"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="panda_link7">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/link7.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/collision/link7.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="1.0517E-2 -4.252E-3 6.1597E-2"/>
<mass value="7.35522E-1"/>
<inertia ixx="1.2516E-2" ixy="-4.28E-4" ixz="-1.19E-3" iyy="1.0027E-2" iyz="-7.41E-4" izz="4.815E-3"/>
</inertial>
</link>
<joint name="panda_joint7" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="1.57079632679 0 0" xyz="0.088 0 0"/>
<parent link="panda_link6"/>
<child link="panda_link7"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.9671" upper="2.9671" velocity="2.8710"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="panda_link8"/>
<joint name="panda_joint8" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.107"/>
<parent link="panda_link7"/>
<child link="panda_link8"/>
<axis xyz="0 0 0"/>
</joint>
<joint name="panda_hand_joint" type="fixed">
<parent link="panda_link8"/>
<child link="panda_hand"/>
<origin rpy="0 0 -0.785398163397" xyz="0 0 0"/>
</joint>
<link name="panda_hand">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/hand.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_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>
<link name="panda_leftfinger">
<visual>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/collision/finger.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.015"/>
<inertia ixx="2.375E-6" ixy="0" ixz="0" iyy="2.375E-6" iyz="0" izz="7.5E-7"/>
</inertial>
</link>
<link name="panda_rightfinger">
<visual>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="package://moveit_resources_panda_description/meshes/collision/finger.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.15"/>
<inertia ixx="2.375E-6" ixy="0" ixz="0" iyy="2.375E-6" iyz="0" izz="7.5E-7"/>
</inertial>
</link>
<joint name="panda_finger_joint1" type="prismatic">
<parent link="panda_hand"/>
<child link="panda_leftfinger"/>
<origin rpy="0 0 0" xyz="0 0 0.0584"/>
<axis xyz="0 1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
<dynamics damping="0.3"/>
</joint>
<joint name="panda_finger_joint2" type="prismatic">
<parent link="panda_hand"/>
<child link="panda_rightfinger"/>
<origin rpy="0 0 0" xyz="0 0 0.0584"/>
<axis xyz="0 -1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
<mimic joint="panda_finger_joint1"/>
<dynamics damping="0.3"/>
</joint>
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="panda_joint1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint2">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">-0.785</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint3">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint4">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">-2.356</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint5">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint6">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">1.571</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint7">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.785</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_finger_joint1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_finger_joint2">
<param name="mimic">panda_finger_joint1</param>
<param name="multiplier">1</param>
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
</ros2_control>
<gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<parameters>$(find moveit_resources_panda_moveit_config)/config/ros2_controllers.yaml</parameters>
</plugin>
</gazebo>
</robot>