gazebo_models/drc_practice_wheel_valve_large/model.sdf
2013-09-04 15:32:31 -07:00

109 lines
2.8 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.4">
<model name="wheel_valve_large">
<link name="handle">
<pose>0 0.0300 0 0 0 0</pose>
<inertial>
<mass>7.8219</mass>
<pose>0 -0.0615 0 0 0 0</pose>
<inertia>
<ixx>0.0695</ixx>
<ixy>0.0000</ixy>
<ixz>0.0000</ixz>
<iyy>0.1349</iyy>
<iyz>0.0000</iyz>
<izz>0.0695</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<mesh>
<uri>model://drc_practice_wheel_valve_large/meshes/wheel_valve_large.dae</uri>
</mesh>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0.01</restitution_coefficient>
<threshold>5.0</threshold>
</bounce>
<friction>
<ode>
<mu>5</mu>
<mu2>5</mu2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0.01 </soft_cfm>
<soft_erp> </soft_erp>
<kp>1000000.0 </kp>
<kd>100000.0 </kd>
<max_vel>0.01 </max_vel>
<min_depth>0.001 </min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://drc_practice_wheel_valve_large/meshes/wheel_valve_large.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<!--
This is just a visual until SDF collide_bitmask is implemented.
Without collide_bitmask, the "attachment" will collide with a
wall that separates the handle from the attachment causing jitter
-->
<!--
<link name="attachment">
<pose>0 0 0.177428906 0 0 0</pose>
<collision name="collision">
<geometry>
<mesh>
<uri>model://drc_practice_ball_valve/meshes/attachment.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<scale>1.6 1.6 1.6</scale>
<uri>model://drc_practice_ball_valve/meshes/attachment.dae</uri>
</mesh>
</geometry>
</visual>
</link>
-->
<joint name="joint" type="revolute">
<parent>world</parent>
<child>handle</child>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-12.56</lower>
<upper>12.56</upper>
</limit>
<dynamics>
<!--velocity dependent viscous damping coefficient of the joint-->
<damping>1000</damping>
<!--default 0, static friction value of the joint-->
<friction>100</friction>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
</model>
</sdf>