|
<?xml version="1.0" encoding="utf-8"?> |
|
|
|
|
|
|
|
|
|
<robot name="franka" xmlns:xacro="http://www.ros.org/wiki/xacro"> |
|
<material name="aluminum"> |
|
<color rgba="0.5 0.5 0.5 1"/> |
|
</material> |
|
|
|
<joint name="camera_joint" type="fixed"> |
|
<origin rpy="0 -1.57079632679 3.14159265359" xyz="0.0358116 0 0.0360562"/> |
|
<parent link="panda_hand"/> |
|
<child link="camera_bottom_screw_frame"/> |
|
</joint> |
|
<link name="camera_bottom_screw_frame"/> |
|
<joint name="camera_link_joint" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0 0.02 0.0115"/> |
|
<parent link="camera_bottom_screw_frame"/> |
|
<child link="camera_link"/> |
|
</joint> |
|
<link name="camera_link"> |
|
<visual> |
|
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.00987 -0.02 0"/> |
|
<geometry> |
|
<box size="0.099 0.023 0.02005"/> |
|
|
|
</geometry> |
|
<material name="aluminum"/> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 -0.02 0"/> |
|
<geometry> |
|
<box size="0.02005 0.099 0.023"/> |
|
</geometry> |
|
</collision> |
|
<inertial> |
|
|
|
<mass value="0.564"/> |
|
<origin xyz="0 0 0"/> |
|
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257"/> |
|
</inertial> |
|
</link> |
|
|
|
<joint name="camera_depth_joint" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
<parent link="camera_link"/> |
|
<child link="camera_depth_frame"/> |
|
</joint> |
|
<link name="camera_depth_frame"/> |
|
<joint name="camera_depth_optical_joint" type="fixed"> |
|
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/> |
|
<parent link="camera_depth_frame"/> |
|
<child link="camera_depth_optical_frame"/> |
|
</joint> |
|
<link name="camera_depth_optical_frame"/> |
|
|
|
<joint name="camera_left_ir_joint" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0 0.0 0"/> |
|
<parent link="camera_depth_frame"/> |
|
<child link="camera_left_ir_frame"/> |
|
</joint> |
|
<link name="camera_left_ir_frame"/> |
|
<joint name="camera_left_ir_optical_joint" type="fixed"> |
|
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/> |
|
<parent link="camera_left_ir_frame"/> |
|
<child link="camera_left_ir_optical_frame"/> |
|
</joint> |
|
<link name="camera_left_ir_optical_frame"/> |
|
|
|
<joint name="camera_right_ir_joint" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0 -0.055 0"/> |
|
<parent link="camera_depth_frame"/> |
|
<child link="camera_right_ir_frame"/> |
|
</joint> |
|
<link name="camera_right_ir_frame"/> |
|
<joint name="camera_right_ir_optical_joint" type="fixed"> |
|
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/> |
|
<parent link="camera_right_ir_frame"/> |
|
<child link="camera_right_ir_optical_frame"/> |
|
</joint> |
|
<link name="camera_right_ir_optical_frame"/> |
|
|
|
<joint name="camera_color_joint" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0 0.015 0"/> |
|
<parent link="camera_depth_frame"/> |
|
<child link="camera_color_frame"/> |
|
</joint> |
|
<link name="camera_color_frame"/> |
|
<joint name="camera_color_optical_joint" type="fixed"> |
|
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/> |
|
<parent link="camera_color_frame"/> |
|
<child link="camera_color_optical_frame"/> |
|
</joint> |
|
<link name="camera_color_optical_frame"/> |
|
<link name="panda_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> |
|
</link> |
|
<link name="panda_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> |
|
</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.8973" upper="2.8973" velocity="2.1750"/> |
|
</joint> |
|
<link name="panda_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> |
|
</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.7628" upper="1.7628" velocity="2.1750"/> |
|
</joint> |
|
<link name="panda_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> |
|
</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.8973" upper="2.8973" velocity="2.1750"/> |
|
</joint> |
|
<link name="panda_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> |
|
</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.0698"/> |
|
<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.0718" upper="-0.0698" velocity="2.1750"/> |
|
</joint> |
|
<link name="panda_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> |
|
</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.8973" upper="2.8973" velocity="2.6100"/> |
|
</joint> |
|
<link name="panda_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> |
|
</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.0175" upper="3.7525" velocity="2.6100"/> |
|
</joint> |
|
<link name="panda_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> |
|
</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.8973" upper="2.8973" velocity="2.6100"/> |
|
</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://franka_description/meshes/visual/hand.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_description/meshes/collision/hand.stl"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<link name="panda_leftfinger"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_description/meshes/visual/finger.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_description/meshes/collision/finger.stl"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<link name="panda_rightfinger"> |
|
<visual> |
|
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/> |
|
<geometry> |
|
<mesh filename="package://franka_description/meshes/visual/finger.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/> |
|
<geometry> |
|
<mesh filename="package://franka_description/meshes/collision/finger.stl"/> |
|
</geometry> |
|
</collision> |
|
</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"/> |
|
</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"/> |
|
</joint> |
|
<link name="base_link"/> |
|
<joint name="base_link_robot" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="base_link"/> |
|
<child link="panda_link0"/> |
|
</joint> |
|
<link name="right_gripper"/> |
|
<joint name="right_gripper" type="fixed"> |
|
<origin rpy="0 0 2.35619449019" xyz="0.0 0 0.1"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_link8"/> |
|
<child link="right_gripper"/> |
|
</joint> |
|
<link name="panda_rightfingertip"/> |
|
<joint name="panda_rightfingertip" type="fixed"> |
|
<origin rpy="0 0 3.14159265359" xyz="0.0 0 0.045"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_rightfinger"/> |
|
<child link="panda_rightfingertip"/> |
|
</joint> |
|
<link name="panda_leftfingertip"/> |
|
<joint name="panda_leftfingertip" type="fixed"> |
|
<origin rpy="0 0 3.14159265359" xyz="0.0 0 0.045"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_leftfinger"/> |
|
<child link="panda_leftfingertip"/> |
|
</joint> |
|
<link name="panda_forearm_end_pt"/> |
|
<joint name="panda_forearm_end_pt" type="fixed"> |
|
<origin rpy="0 0 0.0" xyz="-0.09 0.02 0.0"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_link4"/> |
|
<child link="panda_forearm_end_pt"/> |
|
</joint> |
|
<link name="panda_forearm_mid_pt"/> |
|
<joint name="panda_forearm_mid_pt" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 0.175 0.0"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_forearm_end_pt"/> |
|
<child link="panda_forearm_mid_pt"/> |
|
</joint> |
|
<link name="panda_forearm_mid_pt_shifted"/> |
|
<joint name="panda_forearm_mid_pt_shifted" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 -0.05"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_forearm_mid_pt"/> |
|
<child link="panda_forearm_mid_pt_shifted"/> |
|
</joint> |
|
<link name="panda_forearm_distal"/> |
|
<joint name="panda_forearm_distal" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 0.1 0.0"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_link5"/> |
|
<child link="panda_forearm_distal"/> |
|
</joint> |
|
<link name="panda_wrist_end_pt"/> |
|
<joint name="panda_wrist_end_pt" type="fixed"> |
|
<origin rpy="0 0 0.0" xyz="0.0 0.0 -0.07"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_link7"/> |
|
<child link="panda_wrist_end_pt"/> |
|
</joint> |
|
<link name="panda_face_left"/> |
|
<joint name="panda_face_left" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 0.07 0.04"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_hand"/> |
|
<child link="panda_face_left"/> |
|
</joint> |
|
<link name="panda_face_right"/> |
|
<joint name="panda_face_right" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 -0.07 0.04"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_hand"/> |
|
<child link="panda_face_right"/> |
|
</joint> |
|
<link name="panda_face_back_left"/> |
|
<joint name="panda_face_back_left" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 0.07 0.0"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_hand"/> |
|
<child link="panda_face_back_left"/> |
|
</joint> |
|
<link name="panda_face_back_right"/> |
|
<joint name="panda_face_back_right" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0.0 -0.07 0.0"/> |
|
<axis xyz="0 0 1"/> |
|
<parent link="panda_hand"/> |
|
<child link="panda_face_back_right"/> |
|
</joint> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
</robot> |
|
|
|
|