Skip to content

Commit

Permalink
Move the motor block on top of the bar, use clockwise orientations fo…
Browse files Browse the repository at this point in the history
…r mesh, and adjust angular ranges to +-90 deg
  • Loading branch information
Perrrewi committed Nov 22, 2024
1 parent 918b03f commit 2f7f743
Showing 1 changed file with 8 additions and 10 deletions.
18 changes: 8 additions & 10 deletions models/tiltrotor/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@
</joint>

<link name='motor_0'>
<pose>0.35 -0.35 0.02 0 0 0</pose>
<pose>0.35 -0.35 0.045 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.05</mass>
Expand Down Expand Up @@ -220,8 +220,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.5</lower>
<upper>1.5</upper>
<lower>0.</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<friction>1.0</friction>
Expand All @@ -232,7 +232,6 @@
</axis>
</joint>


<link name='rotor_0'>
<pose>0.35 -0.35 0.07 0 0 0</pose>
<inertial>
Expand Down Expand Up @@ -364,7 +363,7 @@
</joint>

<link name='motor_2'>
<pose>0.35 0.35 0.02 0 0 0</pose>
<pose>0.35 0.35 0.045 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.05</mass>
Expand Down Expand Up @@ -418,8 +417,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.5</lower>
<upper>1.5</upper>
<lower>0.</lower>
<upper>1.57</upper>
</limit>
<dynamics>
<friction>1.0</friction>
Expand All @@ -430,7 +429,6 @@
</axis>
</joint>


<link name='rotor_2'>
<pose>0.35 0.35 0.07 0 0 0</pose>
<inertial>
Expand Down Expand Up @@ -467,7 +465,7 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://tiltrotor/meshes/iris_prop_ccw.dae</uri>
<uri>model://tiltrotor/meshes/iris_prop_cw.dae</uri>
</mesh>
</geometry>
<material> <!-- DarkGrey-->
Expand Down Expand Up @@ -532,7 +530,7 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://tiltrotor/meshes/iris_prop_ccw.dae</uri>
<uri>model://tiltrotor/meshes/iris_prop_cw.dae</uri>
</mesh>
</geometry>
<material> <!-- DarkGrey-->
Expand Down

0 comments on commit 2f7f743

Please sign in to comment.