Skip to content

Commit

Permalink
fixing the links and joints names in typhoon model to reflect the num…
Browse files Browse the repository at this point in the history
…bers of the motors in the px4's hex x airframe
  • Loading branch information
ayhamalharbat committed Jun 5, 2024
1 parent 383a68e commit 727dd25
Showing 1 changed file with 48 additions and 48 deletions.
96 changes: 48 additions & 48 deletions models/typhoon_h480/typhoon_h480.sdf.jinja
Original file line number Diff line number Diff line change
Expand Up @@ -694,7 +694,7 @@
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_3'>
<link name='rotor_2'>
<pose>0.211396 0.119762 0.082219 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand All @@ -708,7 +708,7 @@
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_3_collision'>
<collision name='rotor_2_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
Expand All @@ -725,7 +725,7 @@
</friction>
</surface>
</collision>
<visual name='rotor_3_visual'>
<visual name='rotor_2_visual'>
<pose>-0.211396 -0.119762 -0.082219 0 0 0</pose>
<geometry>
<mesh>
Expand All @@ -744,8 +744,8 @@
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<joint name='rotor_2_joint' type='revolute'>
<child>rotor_2</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
Expand All @@ -766,7 +766,7 @@
</ode>
</physics>
</joint>
<link name='rotor_0'>
<link name='rotor_5'>
<pose>-0.209396 0.122762 0.082219 0 0 2.09439510239</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand All @@ -780,7 +780,7 @@
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_0_collision'>
<collision name='rotor_5_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
Expand All @@ -797,7 +797,7 @@
</friction>
</surface>
</collision>
<visual name='rotor_0_visual'>
<visual name='rotor_5_visual'>
<pose>-0.211396 -0.119762 -0.082219 0 0 0</pose>
<geometry>
<mesh>
Expand All @@ -816,8 +816,8 @@
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_0_joint' type='revolute'>
<child>rotor_0</child>
<joint name='rotor_5_joint' type='revolute'>
<child>rotor_5</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
Expand All @@ -838,7 +838,7 @@
</ode>
</physics>
</joint>
<link name='rotor_4'>
<link name='rotor_1'>
<pose>-0.00187896 0.242705 0.0822169 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand All @@ -852,7 +852,7 @@
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_4_collision'>
<collision name='rotor_1_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
Expand All @@ -869,7 +869,7 @@
</friction>
</surface>
</collision>
<visual name='rotor_4_visual'>
<visual name='rotor_1_visual'>
<pose>0.00187896 -0.242705 -0.0822169 0 0 0</pose>
<geometry>
<mesh>
Expand All @@ -888,8 +888,8 @@
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_4_joint' type='revolute'>
<child>rotor_4</child>
<joint name='rotor_1_joint' type='revolute'>
<child>rotor_1</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
Expand All @@ -910,7 +910,7 @@
</ode>
</physics>
</joint>
<link name='rotor_1'>
<link name='rotor_4'>
<pose>0.211396 -0.119762 0.082219 0 0 -2.09439510239</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand All @@ -924,7 +924,7 @@
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_1_collision'>
<collision name='rotor_4_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
Expand All @@ -941,7 +941,7 @@
</friction>
</surface>
</collision>
<visual name='rotor_1_visual'>
<visual name='rotor_4_visual'>
<pose>0.00187896 -0.242705 -0.0822169 0 0 0</pose>
<geometry>
<mesh>
Expand All @@ -960,8 +960,8 @@
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_1_joint' type='revolute'>
<child>rotor_1</child>
<joint name='rotor_4_joint' type='revolute'>
<child>rotor_4</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
Expand All @@ -983,7 +983,7 @@
</physics>
</joint>

<link name='rotor_5'>
<link name='rotor_0'>
<pose>-0.00187896 -0.242705 0.0822169 0 0 -2.09439510239</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand All @@ -997,7 +997,7 @@
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_5_collision'>
<collision name='rotor_0_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
Expand All @@ -1014,7 +1014,7 @@
</friction>
</surface>
</collision>
<visual name='rotor_5_visual'>
<visual name='rotor_0_visual'>
<pose>-0.211396 -0.119762 -0.082219 0 0 0</pose>
<geometry>
<mesh>
Expand All @@ -1033,8 +1033,8 @@
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_5_joint' type='revolute'>
<child>rotor_5</child>
<joint name='rotor_0_joint' type='revolute'>
<child>rotor_0</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
Expand All @@ -1055,7 +1055,7 @@
</ode>
</physics>
</joint>
<link name='rotor_2'>
<link name='rotor_3'>
<pose>-0.209396 -0.122762 0.082219 0 0 2.09439510239</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand All @@ -1069,7 +1069,7 @@
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_2_collision'>
<collision name='rotor_3_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
Expand All @@ -1086,7 +1086,7 @@
</friction>
</surface>
</collision>
<visual name='rotor_2_visual'>
<visual name='rotor_3_visual'>
<pose>0.00187896 -0.242705 -0.0822169 0 0 0</pose>
<geometry>
<mesh>
Expand All @@ -1105,8 +1105,8 @@
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_2_joint' type='revolute'>
<child>rotor_2</child>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
Expand Down Expand Up @@ -1161,10 +1161,10 @@
<linkName>base_link</linkName>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
<plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace></robotNamespace>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<jointName>rotor_5_joint</jointName>
<linkName>rotor_5</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
Expand All @@ -1178,10 +1178,10 @@
<motorSpeedPubTopic>/motor_speed/5</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
<plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace></robotNamespace>
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<jointName>rotor_4_joint</jointName>
<linkName>rotor_4</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
Expand All @@ -1195,10 +1195,10 @@
<motorSpeedPubTopic>/motor_speed/4</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
<plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace></robotNamespace>
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
Expand All @@ -1212,10 +1212,10 @@
<motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'>
<plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace></robotNamespace>
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
Expand All @@ -1229,10 +1229,10 @@
<motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
<plugin name='left_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace></robotNamespace>
<jointName>rotor_4_joint</jointName>
<linkName>rotor_4</linkName>
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
Expand All @@ -1246,10 +1246,10 @@
<motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
<plugin name='right_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace></robotNamespace>
<jointName>rotor_5_joint</jointName>
<linkName>rotor_5</linkName>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
Expand Down

0 comments on commit 727dd25

Please sign in to comment.