mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
Merged in polaris_differential (pull request #38)
Polaris: rear differential, parameter updates for improved ground contact
This commit is contained in:
commit
aa7db92d85
@ -399,13 +399,15 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>1.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
|
<fdir1>1 0 0</fdir1>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
<contact>
|
<contact>
|
||||||
<ode>
|
<ode>
|
||||||
<min_depth>0.01</min_depth>
|
<min_depth>0.00</min_depth>
|
||||||
|
<kp>1e8</kp>
|
||||||
</ode>
|
</ode>
|
||||||
</contact>
|
</contact>
|
||||||
</surface>
|
</surface>
|
||||||
@ -453,13 +455,15 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>1.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
|
<fdir1>1 0 0</fdir1>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
<contact>
|
<contact>
|
||||||
<ode>
|
<ode>
|
||||||
<min_depth>0.01</min_depth>
|
<min_depth>0.00</min_depth>
|
||||||
|
<kp>1e8</kp>
|
||||||
</ode>
|
</ode>
|
||||||
</contact>
|
</contact>
|
||||||
</surface>
|
</surface>
|
||||||
@ -509,13 +513,15 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>1.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
|
<fdir1>1 0 0</fdir1>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
<contact>
|
<contact>
|
||||||
<ode>
|
<ode>
|
||||||
<min_depth>0.01</min_depth>
|
<min_depth>0.00</min_depth>
|
||||||
|
<kp>1e8</kp>
|
||||||
</ode>
|
</ode>
|
||||||
</contact>
|
</contact>
|
||||||
</surface>
|
</surface>
|
||||||
@ -583,13 +589,15 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.0</mu>
|
<mu>1.0</mu>
|
||||||
<mu2>1.0</mu2>
|
<mu2>1.0</mu2>
|
||||||
|
<fdir1>1 0 0</fdir1>
|
||||||
<slip1>0.0</slip1>
|
<slip1>0.0</slip1>
|
||||||
<slip2>0.0</slip2>
|
<slip2>0.0</slip2>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
<contact>
|
<contact>
|
||||||
<ode>
|
<ode>
|
||||||
<min_depth>0.01</min_depth>
|
<min_depth>0.00</min_depth>
|
||||||
|
<kp>1e8</kp>
|
||||||
</ode>
|
</ode>
|
||||||
</contact>
|
</contact>
|
||||||
</surface>
|
</surface>
|
||||||
@ -915,8 +923,9 @@
|
|||||||
<axis>
|
<axis>
|
||||||
<xyz>0 0 1</xyz>
|
<xyz>0 0 1</xyz>
|
||||||
<limit>
|
<limit>
|
||||||
<lower>-1.0</lower>
|
<!-- +- 50 degrees -->
|
||||||
<upper>1.0</upper>
|
<lower>-0.8727</lower>
|
||||||
|
<upper>0.8727</upper>
|
||||||
</limit>
|
</limit>
|
||||||
<dynamics>
|
<dynamics>
|
||||||
<damping>50.0</damping>
|
<damping>50.0</damping>
|
||||||
@ -946,8 +955,9 @@
|
|||||||
<axis>
|
<axis>
|
||||||
<xyz>0 0 1</xyz>
|
<xyz>0 0 1</xyz>
|
||||||
<limit>
|
<limit>
|
||||||
<lower>-1.0</lower>
|
<!-- +- 50 degrees -->
|
||||||
<upper>1.0</upper>
|
<lower>-0.8727</lower>
|
||||||
|
<upper>0.8727</upper>
|
||||||
</limit>
|
</limit>
|
||||||
<dynamics>
|
<dynamics>
|
||||||
<damping>50.0</damping>
|
<damping>50.0</damping>
|
||||||
@ -990,6 +1000,25 @@
|
|||||||
</axis>
|
</axis>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
<joint type="revolute" name="rear_differential_joint">
|
||||||
|
<child>rear_right_wheel</child>
|
||||||
|
<parent>rear_left_wheel</parent>
|
||||||
|
<axis>
|
||||||
|
<!-- expressed in chassis frame -->
|
||||||
|
<xyz>0 1 0</xyz>
|
||||||
|
<dynamics>
|
||||||
|
<damping>70</damping>
|
||||||
|
</dynamics>
|
||||||
|
</axis>
|
||||||
|
<physics>
|
||||||
|
<ode>
|
||||||
|
<erp>0</erp>
|
||||||
|
<cfm>1000</cfm>
|
||||||
|
<cfm_damping>1</cfm_damping>
|
||||||
|
</ode>
|
||||||
|
</physics>
|
||||||
|
</joint>
|
||||||
|
|
||||||
<joint name='gas_joint' type='prismatic'>
|
<joint name='gas_joint' type='prismatic'>
|
||||||
<parent>chassis</parent>
|
<parent>chassis</parent>
|
||||||
<child>gas_pedal</child>
|
<child>gas_pedal</child>
|
||||||
@ -1000,7 +1029,7 @@
|
|||||||
<upper>0.08</upper>
|
<upper>0.08</upper>
|
||||||
</limit>
|
</limit>
|
||||||
<dynamics>
|
<dynamics>
|
||||||
<damping>3.0</damping>
|
<damping>1.0</damping>
|
||||||
</dynamics>
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
<physics>
|
<physics>
|
||||||
@ -1019,7 +1048,7 @@
|
|||||||
<upper>0.08</upper>
|
<upper>0.08</upper>
|
||||||
</limit>
|
</limit>
|
||||||
<dynamics>
|
<dynamics>
|
||||||
<damping>3.0</damping>
|
<damping>1.0</damping>
|
||||||
</dynamics>
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
<physics>
|
<physics>
|
||||||
@ -1038,7 +1067,15 @@
|
|||||||
<lower>-3.14</lower>
|
<lower>-3.14</lower>
|
||||||
<upper>3.14</upper>
|
<upper>3.14</upper>
|
||||||
</limit>
|
</limit>
|
||||||
|
<dynamics>
|
||||||
|
<damping>1.0</damping>
|
||||||
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
|
<physics>
|
||||||
|
<ode>
|
||||||
|
<cfm_damping>1</cfm_damping>
|
||||||
|
</ode>
|
||||||
|
</physics>
|
||||||
</joint>
|
</joint>
|
||||||
<joint name='hand_brake_joint' type='revolute'>
|
<joint name='hand_brake_joint' type='revolute'>
|
||||||
<parent>chassis</parent>
|
<parent>chassis</parent>
|
||||||
@ -1050,7 +1087,7 @@
|
|||||||
<upper>0.6</upper>
|
<upper>0.6</upper>
|
||||||
</limit>
|
</limit>
|
||||||
<dynamics>
|
<dynamics>
|
||||||
<damping>3.0</damping>
|
<damping>1.0</damping>
|
||||||
</dynamics>
|
</dynamics>
|
||||||
</axis>
|
</axis>
|
||||||
<physics>
|
<physics>
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user