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 26, 2024
1 parent 918b03f commit d868af9
Showing 1 changed file with 34 additions and 12 deletions.
46 changes: 34 additions & 12 deletions models/tiltrotor/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,32 @@
<diffuse>0.175 0.175 0.175 1.0</diffuse>
</material>
</visual>
<visual name='motor_1'>
<pose>-0.35 -0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='motor_3'>
<pose>-0.35 0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
Expand Down Expand Up @@ -166,7 +192,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 +246,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 +258,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 +389,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 +443,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 +455,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 +491,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 +556,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 @@ -846,7 +870,6 @@
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>motor_0_joint</joint_name>
<sub_topic>servo_3</sub_topic>
<motorType>position</motorType>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
Expand Down Expand Up @@ -892,7 +915,6 @@
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>motor_2_joint</joint_name>
<sub_topic>servo_4</sub_topic>
<motorType>position</motorType>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
Expand Down

0 comments on commit d868af9

Please sign in to comment.