mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
Fix wheel friction, add wheel camber to have 1 contact point instead of two, use cfm damping for pedals
This commit is contained in:
parent
aae4f5a94c
commit
02f0fff9c7
@ -11,6 +11,8 @@
|
|||||||
<ixy>0.0</ixy><iyy>550</iyy>
|
<ixy>0.0</ixy><iyy>550</iyy>
|
||||||
<ixz>0.0</ixz><iyz>0.0</iyz><izz>550</izz>
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>550</izz>
|
||||||
</inertia>
|
</inertia>
|
||||||
|
<!-- chassis c.o.g. near lateral/longitudinal center, height of 0.4 m -->
|
||||||
|
<pose>0.1 0 0.4 0 0 0</pose>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual name="visual">
|
<visual name="visual">
|
||||||
<!-- rotate mesh to get to X-forward -->
|
<!-- rotate mesh to get to X-forward -->
|
||||||
@ -376,7 +378,7 @@
|
|||||||
<link_name>atlas::pelvis</link_name>
|
<link_name>atlas::pelvis</link_name>
|
||||||
</plugin-->
|
</plugin-->
|
||||||
<link name="rear_right_wheel">
|
<link name="rear_right_wheel">
|
||||||
<pose>-0.85 -0.6 0.32 1.570796 0.0 0.0</pose>
|
<pose>-0.85 -0.6 0.32 1.52 0.0 0.0</pose>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||||||
<inertia>
|
<inertia>
|
||||||
@ -395,8 +397,8 @@
|
|||||||
<surface>
|
<surface>
|
||||||
<friction>
|
<friction>
|
||||||
<ode>
|
<ode>
|
||||||
<mu>100000.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>100000.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
@ -430,7 +432,7 @@
|
|||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
<link name="rear_left_wheel">
|
<link name="rear_left_wheel">
|
||||||
<pose>-0.85 0.6 0.32 1.570796 0.0 0.0</pose>
|
<pose>-0.85 0.6 0.32 -1.52 0.0 0.0</pose>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||||||
<inertia>
|
<inertia>
|
||||||
@ -449,8 +451,8 @@
|
|||||||
<surface>
|
<surface>
|
||||||
<friction>
|
<friction>
|
||||||
<ode>
|
<ode>
|
||||||
<mu>100000.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>100000.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
@ -486,7 +488,7 @@
|
|||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="front_right_wheel">
|
<link name="front_right_wheel">
|
||||||
<pose>1.03 -0.6 0.32 1.570796 0.0 0.0</pose>
|
<pose>1.03 -0.6 0.32 1.52 0.0 0.0</pose>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||||||
<inertia>
|
<inertia>
|
||||||
@ -505,8 +507,8 @@
|
|||||||
<surface>
|
<surface>
|
||||||
<friction>
|
<friction>
|
||||||
<ode>
|
<ode>
|
||||||
<mu>100000.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>100000.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
@ -560,7 +562,7 @@
|
|||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
<link name="front_left_wheel">
|
<link name="front_left_wheel">
|
||||||
<pose>1.03 0.6 0.32 1.570796 0.0 0.0</pose>
|
<pose>1.03 0.6 0.32 -1.52 0.0 0.0</pose>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||||||
<inertia>
|
<inertia>
|
||||||
@ -579,8 +581,8 @@
|
|||||||
<surface>
|
<surface>
|
||||||
<friction>
|
<friction>
|
||||||
<ode>
|
<ode>
|
||||||
<mu>100000.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>100000.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
@ -593,7 +595,7 @@
|
|||||||
</surface>
|
</surface>
|
||||||
</collision>
|
</collision>
|
||||||
<visual name="visual">
|
<visual name="visual">
|
||||||
<pose>0 0 0 0 -1.570796 0</pose>
|
<pose>0 0 0 3.14159 1.570796 0</pose>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh>
|
<mesh>
|
||||||
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
||||||
@ -728,17 +730,15 @@
|
|||||||
<mass>1.0</mass>
|
<mass>1.0</mass>
|
||||||
<pose>0 0 0 0 0 0</pose>
|
<pose>0 0 0 0 0 0</pose>
|
||||||
<inertia>
|
<inertia>
|
||||||
<ixx>0.1</ixx>
|
<ixx>0.012</ixx>
|
||||||
<ixy>0</ixy>
|
<ixy>0</ixy>
|
||||||
<ixz>0</ixz>
|
<ixz>0</ixz>
|
||||||
<iyy>0.1</iyy>
|
<iyy>0.012</iyy>
|
||||||
<iyz>0</iyz>
|
<iyz>0</iyz>
|
||||||
<izz>1.0</izz>
|
<izz>0.024</izz>
|
||||||
</inertia>
|
</inertia>
|
||||||
</inertial>
|
</inertial>
|
||||||
|
|
||||||
<velocity_decay>0.1</velocity_decay>
|
|
||||||
|
|
||||||
<collision name="collision">
|
<collision name="collision">
|
||||||
<!-- rotate mesh to get to X-forward -->
|
<!-- rotate mesh to get to X-forward -->
|
||||||
<pose>0 0 0 -0.69 0 -1.570796</pose>
|
<pose>0 0 0 -0.69 0 -1.570796</pose>
|
||||||
@ -780,6 +780,16 @@
|
|||||||
</script>
|
</script>
|
||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
|
<!-- visual used to measure size of mesh steering wheel -->
|
||||||
|
<!--visual name="vis_cyl">
|
||||||
|
<pose>0 0 0 0 0 0</pose>
|
||||||
|
<geometry>
|
||||||
|
<cylinder>
|
||||||
|
<radius>0.16</radius>
|
||||||
|
<length>0.01</length>
|
||||||
|
</cylinder>
|
||||||
|
</geometry>
|
||||||
|
</visual-->
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name='hand_brake'>
|
<link name='hand_brake'>
|
||||||
@ -831,22 +841,26 @@
|
|||||||
<lower>-1.0</lower>
|
<lower>-1.0</lower>
|
||||||
<upper>1.0</upper>
|
<upper>1.0</upper>
|
||||||
</limit>
|
</limit>
|
||||||
|
<dynamics>
|
||||||
|
<damping>50.0</damping>
|
||||||
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
<physics><ode><limit>
|
<physics>
|
||||||
<cfm>0.000000</cfm>
|
<ode>
|
||||||
<erp>0.900000</erp>
|
<cfm_damping>1</cfm_damping>
|
||||||
</limit></ode></physics>
|
<limit>
|
||||||
|
<cfm>0.000000</cfm>
|
||||||
|
<erp>0.900000</erp>
|
||||||
|
</limit>
|
||||||
|
</ode>
|
||||||
|
</physics>
|
||||||
</joint>
|
</joint>
|
||||||
<joint type="revolute" name="front_left_wheel_joint">
|
<joint type="revolute" name="front_left_wheel_joint">
|
||||||
<child>front_left_wheel</child>
|
<child>front_left_wheel</child>
|
||||||
<parent>front_left_wheel_steering_block</parent>
|
<parent>front_left_wheel_steering_block</parent>
|
||||||
<axis>
|
<axis>
|
||||||
<xyz>0 1 0</xyz>
|
<xyz>0 1 0.05</xyz>
|
||||||
</axis>
|
</axis>
|
||||||
<physics><ode><limit>
|
|
||||||
<cfm>0.000000</cfm>
|
|
||||||
<erp>0.900000</erp>
|
|
||||||
</limit></ode></physics>
|
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint type="revolute" name="front_right_steering_joint">
|
<joint type="revolute" name="front_right_steering_joint">
|
||||||
@ -858,23 +872,27 @@
|
|||||||
<lower>-1.0</lower>
|
<lower>-1.0</lower>
|
||||||
<upper>1.0</upper>
|
<upper>1.0</upper>
|
||||||
</limit>
|
</limit>
|
||||||
|
<dynamics>
|
||||||
|
<damping>50.0</damping>
|
||||||
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
<physics><ode><limit>
|
<physics>
|
||||||
<cfm>0.000000</cfm>
|
<ode>
|
||||||
<erp>0.900000</erp>
|
<cfm_damping>1</cfm_damping>
|
||||||
</limit></ode></physics>
|
<limit>
|
||||||
|
<cfm>0.000000</cfm>
|
||||||
|
<erp>0.900000</erp>
|
||||||
|
</limit>
|
||||||
|
</ode>
|
||||||
|
</physics>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint type="revolute" name="front_right_wheel_joint">
|
<joint type="revolute" name="front_right_wheel_joint">
|
||||||
<child>front_right_wheel</child>
|
<child>front_right_wheel</child>
|
||||||
<parent>front_right_wheel_steering_block</parent>
|
<parent>front_right_wheel_steering_block</parent>
|
||||||
<axis>
|
<axis>
|
||||||
<xyz>0 1 0</xyz>
|
<xyz>0 1 -0.05</xyz>
|
||||||
</axis>
|
</axis>
|
||||||
<physics><ode><limit>
|
|
||||||
<cfm>0.000000</cfm>
|
|
||||||
<erp>0.900000</erp>
|
|
||||||
</limit></ode></physics>
|
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
@ -882,14 +900,18 @@
|
|||||||
<child>rear_left_wheel</child>
|
<child>rear_left_wheel</child>
|
||||||
<parent>chassis</parent>
|
<parent>chassis</parent>
|
||||||
<axis>
|
<axis>
|
||||||
<xyz>0 1 0</xyz>
|
<xyz>0 1 0.05</xyz>
|
||||||
</axis>
|
</axis>
|
||||||
<physics><ode><limit>
|
|
||||||
<cfm>0.000000</cfm>
|
|
||||||
<erp>0.900000</erp>
|
|
||||||
</limit></ode></physics>
|
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
<joint type="revolute" name="rear_right_wheel_joint">
|
||||||
|
<pose>0.0 0.0 -0.1 0 0 0</pose>
|
||||||
|
<child>rear_right_wheel</child>
|
||||||
|
<parent>chassis</parent>
|
||||||
|
<axis>
|
||||||
|
<xyz>0 1 -0.05</xyz>
|
||||||
|
</axis>
|
||||||
|
</joint>
|
||||||
|
|
||||||
<joint name='gas_joint' type='prismatic'>
|
<joint name='gas_joint' type='prismatic'>
|
||||||
<parent>chassis</parent>
|
<parent>chassis</parent>
|
||||||
@ -900,7 +922,15 @@
|
|||||||
<lower>0.00</lower>
|
<lower>0.00</lower>
|
||||||
<upper>0.08</upper>
|
<upper>0.08</upper>
|
||||||
</limit>
|
</limit>
|
||||||
|
<dynamics>
|
||||||
|
<damping>3.0</damping>
|
||||||
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
|
<physics>
|
||||||
|
<ode>
|
||||||
|
<cfm_damping>1</cfm_damping>
|
||||||
|
</ode>
|
||||||
|
</physics>
|
||||||
</joint>
|
</joint>
|
||||||
<joint name='brake_joint' type='prismatic'>
|
<joint name='brake_joint' type='prismatic'>
|
||||||
<parent>chassis</parent>
|
<parent>chassis</parent>
|
||||||
@ -911,7 +941,15 @@
|
|||||||
<lower>0.00</lower>
|
<lower>0.00</lower>
|
||||||
<upper>0.08</upper>
|
<upper>0.08</upper>
|
||||||
</limit>
|
</limit>
|
||||||
|
<dynamics>
|
||||||
|
<damping>3.0</damping>
|
||||||
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
|
<physics>
|
||||||
|
<ode>
|
||||||
|
<cfm_damping>1</cfm_damping>
|
||||||
|
</ode>
|
||||||
|
</physics>
|
||||||
</joint>
|
</joint>
|
||||||
<joint name='steering_joint' type='revolute'>
|
<joint name='steering_joint' type='revolute'>
|
||||||
<pose>-0.002 0 0 0 0 0</pose>
|
<pose>-0.002 0 0 0 0 0</pose>
|
||||||
@ -934,20 +972,15 @@
|
|||||||
<lower>0</lower>
|
<lower>0</lower>
|
||||||
<upper>0.6</upper>
|
<upper>0.6</upper>
|
||||||
</limit>
|
</limit>
|
||||||
|
<dynamics>
|
||||||
|
<damping>3.0</damping>
|
||||||
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
</joint>
|
<physics>
|
||||||
|
<ode>
|
||||||
<joint type="revolute" name="rear_right_wheel_joint">
|
<cfm_damping>1</cfm_damping>
|
||||||
<pose>0.0 0.0 -0.1 0 0 0</pose>
|
</ode>
|
||||||
<child>rear_right_wheel</child>
|
</physics>
|
||||||
<parent>chassis</parent>
|
|
||||||
<axis>
|
|
||||||
<xyz>0 1 0</xyz>
|
|
||||||
</axis>
|
|
||||||
<physics><ode><limit>
|
|
||||||
<cfm>0.000000</cfm>
|
|
||||||
<erp>0.900000</erp>
|
|
||||||
</limit></ode></physics>
|
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
</model>
|
</model>
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user