You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
Conception/drake-master/examples/planar_gripper/planar_gripper.sdf

601 lines
17 KiB

<?xml version="1.0"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from planar_gripper.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<sdf version="1.7">
<model name="planar_gripper">
<link name="finger1_base">
<visual name="base_visual">
<geometry>
<box>
<size>0.08 0.08 0.008</size>
</box>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
</material>
</visual>
</link>
<link name="finger1_link1">
<inertial>
<pose>0 0 -0.0425 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.0083</ixx>
<iyy>0.0083</iyy>
<izz>5e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="link1_visual">
<pose>0 0 -0.0425 0 0 0</pose>
<geometry>
<cylinder>
<length>0.085</length>
<radius>0.011</radius>
</cylinder>
</geometry>
<material>
<diffuse>1 0 0 1</diffuse>
</material>
</visual>
<visual name="link1_joint_visual">
<pose>0 0 -0.085 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0132</radius>
</sphere>
</geometry>
<material>
<diffuse>.1 .1 .1 1</diffuse>
</material>
</visual>
</link>
<joint name="finger1_BaseJoint" type="revolute">
<child>finger1_link1</child>
<parent>finger1_base</parent>
<axis>
<xyz expressed_in="__model__">1 0 0</xyz>
<limit>
<!-- Drake parses a zero effort joint as an un-actuated joint. -->
<effort>75</effort>
<lower>-1.57</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<damping>0.1</damping>
</dynamics>
</axis>
</joint>
<link name="finger1_link2">
<!-- The origin of the link2 frame is located at the MidJoint. -->
<pose>0 0 -0.085 0 0 0</pose>
<inertial>
<pose>0 0 -0.0299 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.0083</ixx>
<iyy>0.0083</iyy>
<izz>5e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="link2_visual">
<pose>0 0 -0.02 0 0 0</pose>
<geometry>
<cylinder>
<length>0.04</length>
<radius>0.011</radius>
</cylinder>
</geometry>
<material>
<diffuse>1 0 0 1</diffuse>
</material>
</visual>
<!--The link 2 collision element extends up to (but not including) the
sphere fingertip-->
<collision name="link2_collision">
<pose>0 0 -0.0299 0 0 0</pose>
<geometry>
<box>
<size> 0.022 0.022 0.0598 </size>
</box>
</geometry>
</collision>
<visual name="sensor_visual">
<pose>0 0 -0.0425 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.02 0.005</size>
</box>
</geometry>
<material>
<diffuse>.8 .8 .8 1</diffuse>
</material>
</visual>
</link>
<joint name="finger1_MidJoint" type="revolute">
<parent>finger1_link1</parent>
<child>finger1_link2</child>
<!-- Pose X_CJ of the joint frame J in the frame C of the child link -->
<axis>
<xyz expressed_in="__model__">1 0 0</xyz>
<limit>
<effort>75</effort>
<lower>-1.57</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<damping>0.1</damping>
</dynamics>
</axis>
</joint>
<!-- The tip link's mass/inertia values are already included in link 2,
which welds to this link. Hence, the values here are set to be
(effectively) zero. Note: This fingertip link and its corresponding
weld joint allows us to sense forces via MBP's reaction forces
output port. -->
<link name="finger1_tip_link">
<pose>0 0 -0.13 0 0 0</pose>
<inertial>
<pose>0 0 -0.0074 0 0 0</pose>
<mass>1e-7</mass>
<inertia>
<ixx>1e-7</ixx>
<iyy>1e-7</iyy>
<izz>1e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="tip_adapter_visual">
<pose>0 0 -0.00565 0 0 0</pose>
<geometry>
<cylinder>
<length>0.0113</length>
<radius>0.0145</radius>
</cylinder>
</geometry>
<material>
<diffuse>.3 .3 .3 1</diffuse>
</material>
</visual>
<visual name="tip_cylinder_visual">
<pose>0 0 -0.01305 0 0 0</pose>
<geometry>
<cylinder>
<length>0.0035</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<diffuse>.3 .3 .3 1</diffuse>
</material>
</visual>
<visual name="tip_sphere_visual">
<pose>0 0 -0.0263 0 0 0</pose>
<geometry>
<sphere>
<radius>0.015</radius>
</sphere>
</geometry>
<material>
<diffuse>1 1 1 1</diffuse>
</material>
</visual>
<collision name="tip_sphere_collision">
<pose>0 0 -0.0263 0 0 0</pose>
<geometry>
<sphere>
<radius>0.015</radius>
</sphere>
</geometry>
</collision>
</link>
<joint name="finger1_sensor_weldjoint" type="fixed">
<parent>finger1_link2</parent>
<child>finger1_tip_link</child>
</joint>
<link name="finger2_base">
<visual name="base_visual">
<geometry>
<box>
<size>0.08 0.08 0.008</size>
</box>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
</material>
</visual>
</link>
<link name="finger2_link1">
<inertial>
<pose>0 0 -0.0425 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.0083</ixx>
<iyy>0.0083</iyy>
<izz>5e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="link1_visual">
<pose>0 0 -0.0425 0 0 0</pose>
<geometry>
<cylinder>
<length>0.085</length>
<radius>0.011</radius>
</cylinder>
</geometry>
<material>
<diffuse>1 0 0 1</diffuse>
</material>
</visual>
<visual name="link1_joint_visual">
<pose>0 0 -0.085 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0132</radius>
</sphere>
</geometry>
<material>
<diffuse>.1 .1 .1 1</diffuse>
</material>
</visual>
</link>
<joint name="finger2_BaseJoint" type="revolute">
<child>finger2_link1</child>
<parent>finger2_base</parent>
<axis>
<xyz expressed_in="__model__">1 0 0</xyz>
<limit>
<!-- Drake parses a zero effort joint as an un-actuated joint. -->
<effort>75</effort>
<lower>-1.57</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<damping>0.1</damping>
</dynamics>
</axis>
</joint>
<link name="finger2_link2">
<!-- The origin of the link2 frame is located at the MidJoint. -->
<pose>0 0 -0.085 0 0 0</pose>
<inertial>
<pose>0 0 -0.0299 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.0083</ixx>
<iyy>0.0083</iyy>
<izz>5e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="link2_visual">
<pose>0 0 -0.02 0 0 0</pose>
<geometry>
<cylinder>
<length>0.04</length>
<radius>0.011</radius>
</cylinder>
</geometry>
<material>
<diffuse>1 0 0 1</diffuse>
</material>
</visual>
<!--The link 2 collision element extends up to (but not including) the
sphere fingertip-->
<collision name="link2_collision">
<pose>0 0 -0.0299 0 0 0</pose>
<geometry>
<box>
<size> 0.022 0.022 0.0598 </size>
</box>
</geometry>
</collision>
<visual name="sensor_visual">
<pose>0 0 -0.0425 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.02 0.005</size>
</box>
</geometry>
<material>
<diffuse>.8 .8 .8 1</diffuse>
</material>
</visual>
</link>
<joint name="finger2_MidJoint" type="revolute">
<parent>finger2_link1</parent>
<child>finger2_link2</child>
<!-- Pose X_CJ of the joint frame J in the frame C of the child link -->
<axis>
<xyz expressed_in="__model__">1 0 0</xyz>
<limit>
<effort>75</effort>
<lower>-1.57</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<damping>0.1</damping>
</dynamics>
</axis>
</joint>
<!-- The tip link's mass/inertia values are already included in link 2,
which welds to this link. Hence, the values here are set to be
(effectively) zero. Note: This fingertip link and its corresponding
weld joint allows us to sense forces via MBP's reaction forces
output port. -->
<link name="finger2_tip_link">
<pose>0 0 -0.13 0 0 0</pose>
<inertial>
<pose>0 0 -0.0074 0 0 0</pose>
<mass>1e-7</mass>
<inertia>
<ixx>1e-7</ixx>
<iyy>1e-7</iyy>
<izz>1e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="tip_adapter_visual">
<pose>0 0 -0.00565 0 0 0</pose>
<geometry>
<cylinder>
<length>0.0113</length>
<radius>0.0145</radius>
</cylinder>
</geometry>
<material>
<diffuse>.3 .3 .3 1</diffuse>
</material>
</visual>
<visual name="tip_cylinder_visual">
<pose>0 0 -0.01305 0 0 0</pose>
<geometry>
<cylinder>
<length>0.0035</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<diffuse>.3 .3 .3 1</diffuse>
</material>
</visual>
<visual name="tip_sphere_visual">
<pose>0 0 -0.0263 0 0 0</pose>
<geometry>
<sphere>
<radius>0.015</radius>
</sphere>
</geometry>
<material>
<diffuse>1 1 1 1</diffuse>
</material>
</visual>
<collision name="tip_sphere_collision">
<pose>0 0 -0.0263 0 0 0</pose>
<geometry>
<sphere>
<radius>0.015</radius>
</sphere>
</geometry>
</collision>
</link>
<joint name="finger2_sensor_weldjoint" type="fixed">
<parent>finger2_link2</parent>
<child>finger2_tip_link</child>
</joint>
<link name="finger3_base">
<visual name="base_visual">
<geometry>
<box>
<size>0.08 0.08 0.008</size>
</box>
</geometry>
<material>
<diffuse>0.1 0.1 0.1 1</diffuse>
</material>
</visual>
</link>
<link name="finger3_link1">
<inertial>
<pose>0 0 -0.0425 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.0083</ixx>
<iyy>0.0083</iyy>
<izz>5e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="link1_visual">
<pose>0 0 -0.0425 0 0 0</pose>
<geometry>
<cylinder>
<length>0.085</length>
<radius>0.011</radius>
</cylinder>
</geometry>
<material>
<diffuse>1 0 0 1</diffuse>
</material>
</visual>
<visual name="link1_joint_visual">
<pose>0 0 -0.085 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0132</radius>
</sphere>
</geometry>
<material>
<diffuse>.1 .1 .1 1</diffuse>
</material>
</visual>
</link>
<joint name="finger3_BaseJoint" type="revolute">
<child>finger3_link1</child>
<parent>finger3_base</parent>
<axis>
<xyz expressed_in="__model__">1 0 0</xyz>
<limit>
<!-- Drake parses a zero effort joint as an un-actuated joint. -->
<effort>75</effort>
<lower>-1.57</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<damping>0.1</damping>
</dynamics>
</axis>
</joint>
<link name="finger3_link2">
<!-- The origin of the link2 frame is located at the MidJoint. -->
<pose>0 0 -0.085 0 0 0</pose>
<inertial>
<pose>0 0 -0.0299 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.0083</ixx>
<iyy>0.0083</iyy>
<izz>5e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="link2_visual">
<pose>0 0 -0.02 0 0 0</pose>
<geometry>
<cylinder>
<length>0.04</length>
<radius>0.011</radius>
</cylinder>
</geometry>
<material>
<diffuse>1 0 0 1</diffuse>
</material>
</visual>
<!--The link 2 collision element extends up to (but not including) the
sphere fingertip-->
<collision name="link2_collision">
<pose>0 0 -0.0299 0 0 0</pose>
<geometry>
<box>
<size> 0.022 0.022 0.0598 </size>
</box>
</geometry>
</collision>
<visual name="sensor_visual">
<pose>0 0 -0.0425 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.02 0.005</size>
</box>
</geometry>
<material>
<diffuse>.8 .8 .8 1</diffuse>
</material>
</visual>
</link>
<joint name="finger3_MidJoint" type="revolute">
<parent>finger3_link1</parent>
<child>finger3_link2</child>
<!-- Pose X_CJ of the joint frame J in the frame C of the child link -->
<axis>
<xyz expressed_in="__model__">1 0 0</xyz>
<limit>
<effort>75</effort>
<lower>-1.57</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<damping>0.1</damping>
</dynamics>
</axis>
</joint>
<!-- The tip link's mass/inertia values are already included in link 2,
which welds to this link. Hence, the values here are set to be
(effectively) zero. Note: This fingertip link and its corresponding
weld joint allows us to sense forces via MBP's reaction forces
output port. -->
<link name="finger3_tip_link">
<pose>0 0 -0.13 0 0 0</pose>
<inertial>
<pose>0 0 -0.0074 0 0 0</pose>
<mass>1e-7</mass>
<inertia>
<ixx>1e-7</ixx>
<iyy>1e-7</iyy>
<izz>1e-7</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="tip_adapter_visual">
<pose>0 0 -0.00565 0 0 0</pose>
<geometry>
<cylinder>
<length>0.0113</length>
<radius>0.0145</radius>
</cylinder>
</geometry>
<material>
<diffuse>.3 .3 .3 1</diffuse>
</material>
</visual>
<visual name="tip_cylinder_visual">
<pose>0 0 -0.01305 0 0 0</pose>
<geometry>
<cylinder>
<length>0.0035</length>
<radius>0.01</radius>
</cylinder>
</geometry>
<material>
<diffuse>.3 .3 .3 1</diffuse>
</material>
</visual>
<visual name="tip_sphere_visual">
<pose>0 0 -0.0263 0 0 0</pose>
<geometry>
<sphere>
<radius>0.015</radius>
</sphere>
</geometry>
<material>
<diffuse>1 1 1 1</diffuse>
</material>
</visual>
<collision name="tip_sphere_collision">
<pose>0 0 -0.0263 0 0 0</pose>
<geometry>
<sphere>
<radius>0.015</radius>
</sphere>
</geometry>
</collision>
</link>
<joint name="finger3_sensor_weldjoint" type="fixed">
<parent>finger3_link2</parent>
<child>finger3_tip_link</child>
</joint>
</model>
</sdf>