model.sdf 1.79 KB
<?xml version="1.0" ?>
<sdf version="1.5">
  <model name="parachute_small">
    <pose>0 0 0 0 0 0</pose>
    <static>false</static>

    <link name="chute">
      <pose>0 0 0  0 0 0</pose>
      <inertial>
        <pose>0 0 0  0 0 0</pose>
        <mass>0.100000</mass>
        <inertia>
          <ixx>0.010000</ixx>
          <ixy>0.000000</ixy>
          <ixz>0.000000</ixz>
          <iyy>0.010000</iyy>
          <iyz>0.000000</iyz>
          <izz>0.010000</izz>
        </inertia>
      </inertial>
      <collision name="parachute_collision">
        <pose>0 0 1.25  0 0 0</pose>
        <geometry>
          <cylinder>
            <radius>0.35</radius>
            <length>0.4</length>
          </cylinder>
        </geometry>
      </collision>
      <visual name="parachute_vis">
        <pose>-0.000000 0.000000 0.000000 0.000000 -0.000000 0.000000</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://parachute_small/meshes/parachute_small.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <velocity_decay />
    </link>

    <plugin name="parachute_drag" filename="libLiftDragPlugin.so">
      <a0>0</a0>
      <cla>0</cla>
      <cda>1.114</cda>  <!-- Such that Cd = 1.75 at alpha = 90deg (= upright parachute) -->
      <cma>0</cma>
      <alpha_stall>1.5708</alpha_stall> <!-- = upright parachute -->
      <cla_stall>0</cla_stall>
      <cda_stall>0.01</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>0 0 1.25</cp>   <!-- About the vertical center of the chute -->
      <area>3</area>   <!-- Area of a circle of diameter 1m = 0.79, 3m2 is for a better visualization -->
      <air_density>1.2041</air_density>
      <forward>1 0 0</forward>
      <upward>0 0 1</upward>
      <link_name>chute</link_name>
    </plugin>
    

  </model>
</sdf>