Adding control surfaces to the cessna model.

This commit is contained in:
Carlos Agüero 2015-05-27 13:25:46 -07:00
parent 0d1b52f7e2
commit 2c8f1d004f
8 changed files with 1904 additions and 6371 deletions

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -64,7 +64,7 @@
</link>
<link name="left_exterior_wing">
<link name="left_aileron">
<inertial>
<mass>2</mass>
<inertia>
@ -81,7 +81,7 @@
<collision name="collision">
<geometry>
<mesh>
<uri>model://cessna/meshes/left_exterior_wing.dae</uri>
<uri>model://cessna/meshes/left_aileron.dae</uri>
</mesh>
</geometry>
</collision>
@ -89,13 +89,13 @@
<visual name="visual">
<geometry>
<mesh>
<uri>model://cessna/meshes/left_exterior_wing.dae</uri>
<uri>model://cessna/meshes/left_aileron.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<link name="left_interior_wing">
<link name="left_flap">
<inertial>
<mass>2</mass>
<inertia>
@ -112,7 +112,7 @@
<collision name="collision">
<geometry>
<mesh>
<uri>model://cessna/meshes/left_interior_wing.dae</uri>
<uri>model://cessna/meshes/left_flap.dae</uri>
</mesh>
</geometry>
</collision>
@ -120,13 +120,13 @@
<visual name="visual">
<geometry>
<mesh>
<uri>model://cessna/meshes/left_interior_wing.dae</uri>
<uri>model://cessna/meshes/left_flap.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<link name="right_exterior_wing">
<link name="right_aileron">
<inertial>
<mass>2</mass>
<inertia>
@ -143,7 +143,7 @@
<collision name="collision">
<geometry>
<mesh>
<uri>model://cessna/meshes/right_exterior_wing.dae</uri>
<uri>model://cessna/meshes/right_aileron.dae</uri>
</mesh>
</geometry>
</collision>
@ -151,13 +151,13 @@
<visual name="visual">
<geometry>
<mesh>
<uri>model://cessna/meshes/right_exterior_wing.dae</uri>
<uri>model://cessna/meshes/right_aileron.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<link name="right_interior_wing">
<link name="right_flap">
<inertial>
<mass>2</mass>
<inertia>
@ -174,7 +174,7 @@
<collision name="collision">
<geometry>
<mesh>
<uri>model://cessna/meshes/right_interior_wing.dae</uri>
<uri>model://cessna/meshes/right_flap.dae</uri>
</mesh>
</geometry>
</collision>
@ -182,13 +182,13 @@
<visual name="visual">
<geometry>
<mesh>
<uri>model://cessna/meshes/right_interior_wing.dae</uri>
<uri>model://cessna/meshes/right_flap.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<link name="stabilizer">
<link name="elevators">
<inertial>
<mass>2</mass>
<inertia>
@ -205,7 +205,7 @@
<collision name="collision">
<geometry>
<mesh>
<uri>model://cessna/meshes/stabilizer.dae</uri>
<uri>model://cessna/meshes/elevators.dae</uri>
</mesh>
</geometry>
</collision>
@ -213,7 +213,7 @@
<visual name="visual">
<geometry>
<mesh>
<uri>model://cessna/meshes/stabilizer.dae</uri>
<uri>model://cessna/meshes/elevators.dae</uri>
</mesh>
</geometry>
</visual>
@ -421,13 +421,114 @@
</visual>
</link>
<!-- Joint to move the left flap -->
<joint name='left_flap_joint' type='revolute'>
<parent>body</parent>
<child>left_flap</child>
<pose>-1.6 1.55 1.43 0.02 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
</axis>
</joint>
<!-- Joint to move the left aileron -->
<joint name='left_aileron_joint' type='revolute'>
<parent>body</parent>
<child>left_aileron</child>
<pose>-1.45 3.7 1.5 0.05 0 -0.12</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
</axis>
</joint>
<!-- Joint to move the right flap -->
<joint name='right_flap_joint' type='revolute'>
<parent>body</parent>
<child>right_flap</child>
<pose>-1.6 -1.55 1.43 -0.02 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
</axis>
</joint>
<!-- Joint to move the right aileron -->
<joint name='right_aileron_joint' type='revolute'>
<parent>body</parent>
<child>right_aileron</child>
<pose>-1.45 -3.7 1.5 -0.05 0 0.12</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
</axis>
</joint>
<!-- Joint to move the elevators -->
<joint name='elevators_joint' type='revolute'>
<parent>body</parent>
<child>elevators</child>
<pose>-5.55 0 0.57 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
</axis>
</joint>
<!-- Joint to move the rudder -->
<joint name='rudder_joint' type='revolute'>
<parent>body</parent>
<child>rudder</child>
<pose>-5.9 0 1.3 0 -0.35 0</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
</axis>
</joint>
<!-- Joint to make the propeller spin -->
<joint name='propeller_joint' type='revolute'>
<parent>body</parent>
<child>propeller</child>
<axis>
<xyz>1 0 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+12</lower>
<upper>1e+12</upper>
@ -444,7 +545,6 @@
<pose>0.712 0 -0.313 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+12</lower>
<upper>1e+12</upper>
@ -461,7 +561,6 @@
<pose>-1 -1.27 -0.25 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+12</lower>
<upper>1e+12</upper>
@ -478,7 +577,6 @@
<pose>-1 1.27 -0.25 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+12</lower>
<upper>1e+12</upper>