mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
wheels and bottom
This commit is contained in:
parent
a45e1a43c1
commit
4a6987931d
@ -2,21 +2,154 @@
|
|||||||
<sdf version="1.3">
|
<sdf version="1.3">
|
||||||
<model name="Polaris Ranger EV">
|
<model name="Polaris Ranger EV">
|
||||||
<link name="chassis">
|
<link name="chassis">
|
||||||
<pose>0 0 0 0 0 0</pose>
|
<inertial>
|
||||||
<collision name="collision">
|
<mass>500.0</mass>
|
||||||
<geometry>
|
</inertial>
|
||||||
<mesh>
|
|
||||||
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
|
||||||
</mesh>
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
<visual name="visual">
|
<visual name="visual">
|
||||||
|
<!-- rotate mesh to get to X-forward -->
|
||||||
|
<pose>0 0 0 0 0 -1.507</pose>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh>
|
<mesh>
|
||||||
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
||||||
</mesh>
|
</mesh>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
|
<collision name="chassis_bottom">
|
||||||
|
<pose>0.0 0.0 0.3 0.0 0.0 0.0</pose>
|
||||||
|
<geometry>
|
||||||
|
<box>
|
||||||
|
<size>2.0 1.0 0.01</size>
|
||||||
|
</box>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
<link name="rear_right_wheel">
|
||||||
|
<pose>-0.85 -0.675 0.3 1.5708 0.0 0.0</pose>
|
||||||
|
<inertial>
|
||||||
|
<mass>0.5</mass>
|
||||||
|
</inertial>
|
||||||
|
<collision name="collision">
|
||||||
|
<geometry>
|
||||||
|
<cylinder>
|
||||||
|
<radius>0.3</radius>
|
||||||
|
<length>0.2</length>
|
||||||
|
</cylinder>
|
||||||
|
</geometry>
|
||||||
|
<surface>
|
||||||
|
<friction>
|
||||||
|
<ode>
|
||||||
|
<mu>100000.0</mu>
|
||||||
|
<mu2>100000.0</mu2>
|
||||||
|
<slip1>0.0</slip1>
|
||||||
|
<slip2>0.0</slip2>
|
||||||
|
</ode>
|
||||||
|
</friction>
|
||||||
|
</surface>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<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</xyz>
|
||||||
|
</axis>
|
||||||
|
</joint>
|
||||||
|
<link name="rear_left_wheel">
|
||||||
|
<pose>-0.85 0.575 0.3 1.5708 0.0 0.0</pose>
|
||||||
|
<inertial>
|
||||||
|
<mass>0.5</mass>
|
||||||
|
</inertial>
|
||||||
|
<collision name="collision">
|
||||||
|
<geometry>
|
||||||
|
<cylinder>
|
||||||
|
<radius>0.3</radius>
|
||||||
|
<length>0.2</length>
|
||||||
|
</cylinder>
|
||||||
|
</geometry>
|
||||||
|
<surface>
|
||||||
|
<friction>
|
||||||
|
<ode>
|
||||||
|
<mu>100000.0</mu>
|
||||||
|
<mu2>100000.0</mu2>
|
||||||
|
<slip1>0.0</slip1>
|
||||||
|
<slip2>0.0</slip2>
|
||||||
|
</ode>
|
||||||
|
</friction>
|
||||||
|
</surface>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint type="revolute" name="rear_left_wheel_joint">
|
||||||
|
<pose>0.0 0.0 0.1 0 0 0</pose>
|
||||||
|
<child>rear_left_wheel</child>
|
||||||
|
<parent>chassis</parent>
|
||||||
|
<axis>
|
||||||
|
<xyz>0 1 0</xyz>
|
||||||
|
</axis>
|
||||||
|
</joint>
|
||||||
|
<link name="front_right_wheel">
|
||||||
|
<pose>1.03 -0.55 0.3 1.5708 0.0 0.0</pose>
|
||||||
|
<inertial>
|
||||||
|
<mass>0.5</mass>
|
||||||
|
</inertial>
|
||||||
|
<collision name="collision">
|
||||||
|
<geometry>
|
||||||
|
<cylinder>
|
||||||
|
<radius>0.3</radius>
|
||||||
|
<length>0.2</length>
|
||||||
|
</cylinder>
|
||||||
|
</geometry>
|
||||||
|
<surface>
|
||||||
|
<friction>
|
||||||
|
<ode>
|
||||||
|
<mu>100000.0</mu>
|
||||||
|
<mu2>100000.0</mu2>
|
||||||
|
<slip1>0.0</slip1>
|
||||||
|
<slip2>0.0</slip2>
|
||||||
|
</ode>
|
||||||
|
</friction>
|
||||||
|
</surface>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint type="revolute" name="front_right_wheel_joint">
|
||||||
|
<pose>0.0 0.0 -0.1 0 0 0</pose>
|
||||||
|
<child>front_right_wheel</child>
|
||||||
|
<parent>chassis</parent>
|
||||||
|
<axis>
|
||||||
|
<xyz>0 1 0</xyz>
|
||||||
|
</axis>
|
||||||
|
</joint>
|
||||||
|
<link name="front_left_wheel">
|
||||||
|
<pose>1.03 0.65 0.3 1.5708 0.0 0.0</pose>
|
||||||
|
<inertial>
|
||||||
|
<mass>0.5</mass>
|
||||||
|
</inertial>
|
||||||
|
<collision name="collision">
|
||||||
|
<geometry>
|
||||||
|
<cylinder>
|
||||||
|
<radius>0.3</radius>
|
||||||
|
<length>0.2</length>
|
||||||
|
</cylinder>
|
||||||
|
</geometry>
|
||||||
|
<surface>
|
||||||
|
<friction>
|
||||||
|
<ode>
|
||||||
|
<mu>100000.0</mu>
|
||||||
|
<mu2>100000.0</mu2>
|
||||||
|
<slip1>0.0</slip1>
|
||||||
|
<slip2>0.0</slip2>
|
||||||
|
</ode>
|
||||||
|
</friction>
|
||||||
|
</surface>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
<joint type="revolute" name="front_left_wheel_joint">
|
||||||
|
<pose>0.0 0.0 0.1 0 0 0</pose>
|
||||||
|
<child>front_left_wheel</child>
|
||||||
|
<parent>chassis</parent>
|
||||||
|
<axis>
|
||||||
|
<xyz>0 1 0</xyz>
|
||||||
|
</axis>
|
||||||
|
</joint>
|
||||||
</model>
|
</model>
|
||||||
</sdf>
|
</sdf>
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user