mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
Fix steering wheel axis and submesh alignment
This commit is contained in:
parent
2ed186a862
commit
b5c7696d5a
@ -313,6 +313,16 @@
|
|||||||
</material>
|
</material>
|
||||||
</visual>
|
</visual>
|
||||||
-->
|
-->
|
||||||
|
<!-- the following was used as a guide for aligning the steering wheel mesh -->
|
||||||
|
<!--visual name="visual_steering_cylinder">
|
||||||
|
<pose>0.35 0.30 1.3 0 -0.87 0</pose>
|
||||||
|
<geometry>
|
||||||
|
<cylinder>
|
||||||
|
<radius>0.17</radius>
|
||||||
|
<length>0.01</length>
|
||||||
|
</cylinder>
|
||||||
|
</geometry>
|
||||||
|
</visual-->
|
||||||
</link>
|
</link>
|
||||||
<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.570796 0.0 0.0</pose>
|
||||||
@ -642,7 +652,7 @@
|
|||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name='steering_wheel'>
|
<link name='steering_wheel'>
|
||||||
<pose>0.37 0.30 1.3 0 -0.8 0</pose>
|
<pose>0.34 0.30 1.29 0 -0.87 0</pose>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass>1.0</mass>
|
<mass>1.0</mass>
|
||||||
<pose>0 0 0 0 0 0</pose>
|
<pose>0 0 0 0 0 0</pose>
|
||||||
@ -660,7 +670,7 @@
|
|||||||
|
|
||||||
<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.8 0 -1.570796</pose>
|
<pose>0 0 0 -0.69 0 -1.570796</pose>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh>
|
<mesh>
|
||||||
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
||||||
@ -674,7 +684,7 @@
|
|||||||
|
|
||||||
<visual name="visual">
|
<visual name="visual">
|
||||||
<!-- rotate mesh to get to X-forward -->
|
<!-- rotate mesh to get to X-forward -->
|
||||||
<pose>0 0 0 -0.8 0 -1.570796</pose>
|
<pose>0 0 0 -0.69 0 -1.570796</pose>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh>
|
<mesh>
|
||||||
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
|
||||||
@ -826,14 +836,14 @@
|
|||||||
</axis>
|
</axis>
|
||||||
</joint>
|
</joint>
|
||||||
<joint name='steering_joint' type='revolute'>
|
<joint name='steering_joint' type='revolute'>
|
||||||
<pose>0 0 0 1.570796 -0.8 0.0</pose>
|
<pose>-0.002 0 0 0 0 0</pose>
|
||||||
<parent>chassis</parent>
|
<parent>chassis</parent>
|
||||||
<child>steering_wheel</child>
|
<child>steering_wheel</child>
|
||||||
<axis>
|
<axis>
|
||||||
<xyz>-1 0 1.023</xyz>
|
<xyz>-1 0 0.84365</xyz>
|
||||||
<limit>
|
<limit>
|
||||||
<lower>-7.853000</lower>
|
<lower>-3.14</lower>
|
||||||
<upper>7.853000</upper>
|
<upper>3.14</upper>
|
||||||
</limit>
|
</limit>
|
||||||
</axis>
|
</axis>
|
||||||
</joint>
|
</joint>
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user