Merged in issue_24 (pull request #106)

fix issue #24 and minor updates to physics params
This commit is contained in:
Nathan Koenig 2014-11-21 09:47:10 -08:00
commit c795b0d76c

View File

@ -2,7 +2,7 @@
<sdf version="1.5"> <sdf version="1.5">
<model name="wheel_valve_large"> <model name="wheel_valve_large">
<link name="handle"> <link name="handle">
<pose>0 0.0300 0 0 0 0</pose> <pose>0 0.0310 0 0 0 0</pose>
<inertial> <inertial>
<mass>7.8219</mass> <mass>7.8219</mass>
<pose>0 0.0615 0 0 0 0</pose> <pose>0 0.0615 0 0 0 0</pose>
@ -22,22 +22,16 @@
</mesh> </mesh>
</geometry> </geometry>
<surface> <surface>
<bounce>
<restitution_coefficient>0.01</restitution_coefficient>
<threshold>5.0</threshold>
</bounce>
<friction> <friction>
<ode> <ode>
<mu>5</mu> <mu>1</mu>
<mu2>5</mu2> <mu2>1</mu2>
</ode> </ode>
</friction> </friction>
<contact> <contact>
<ode> <ode>
<soft_cfm>0.01</soft_cfm>
<soft_erp />
<kp>1000000.0</kp> <kp>1000000.0</kp>
<kd>100000.0</kd> <kd>100.0</kd>
<max_vel>0.01</max_vel> <max_vel>0.01</max_vel>
<min_depth>0.001</min_depth> <min_depth>0.001</min_depth>
</ode> </ode>
@ -89,11 +83,11 @@
</limit> </limit>
<dynamics> <dynamics>
<!--velocity dependent viscous damping coefficient of the joint--> <!--velocity dependent viscous damping coefficient of the joint-->
<damping>0</damping> <damping>0.1</damping>
<!--default 0, static friction value of the joint--> <!--default 0, static friction value of the joint-->
<friction>0</friction> <friction>0.1</friction>
</dynamics> </dynamics>
<use_parent_model_frame>true</use_parent_model_frame> <use_parent_model_frame>false</use_parent_model_frame>
</axis> </axis>
<physics> <physics>
<ode> <ode>