X8 octa-quad SITL gazebo

Hello again. I have changed the size of the Iris to 1.5 1.6 1 to resemble my drone (and the other values above as I mentioned earlier.) It takes off but it starts to take a big angle and eventually crashes, right after it reaches the desired height.

AP: Vibration compensation ON
height 5
AP: Crash: Disarming: AngErr=172>30, Accel=0.3<3.0


When I change the propellers parameters and inertia I have this issue, so I guess the cp and area are not correct? As I said earlier I tried to do the scaling you proposed on an other thread, depending on my motors.

Any help will be appreciated.

The easiest way to help is if you can share the SDF of the copter you are trying to simulate. That way it will be possible to replicate the set up, and try and fix configuration issues. It’s difficult to do this without the model.

Here are the sdf files:

Iris with ardupilot

<?xml version="1.0"?>

<sdf version="1.9">

  <model name="iris_with_ardupilot">

    <include>

      <uri>model://iris_with_standoffs</uri>

    </include>





    <!-- plugins -->

    <plugin filename="gz-sim-joint-state-publisher-system"

      name="gz::sim::systems::JointStatePublisher">

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_1_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_1_link</link_name>

    </plugin>



    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_2_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_2_link</link_name>

    </plugin>



    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_3_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_3_link</link_name>

    </plugin>



    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_4_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_4_link</link_name>

    </plugin>



    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_5_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_5_link</link_name>

    </plugin>



    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_6_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_6_link</link_name>

    </plugin>



    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_7_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_7_link</link_name>

    </plugin>



    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>0.3024 0 0</cp>

      <forward>0 -1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_8_link</link_name>

    </plugin>

    <plugin filename="gz-sim-lift-drag-system"

        name="gz::sim::systems::LiftDrag">

      <a0>0.3</a0>

      <alpha_stall>1.4</alpha_stall>

      <cla>4.2500</cla>

      <cda>0.10</cda>

      <cma>0.0</cma>

      <cla_stall>-0.025</cla_stall>

      <cda_stall>0.0</cda_stall>

      <cma_stall>0.0</cma_stall>

      <area>0.0144</area>

      <air_density>1.2041</air_density>

      <cp>-0.3024 0 0</cp>

      <forward>0 1 0</forward>

      <upward>0 0 1</upward>

      <link_name>iris_with_standoffs::rotor_8_link</link_name>

    </plugin>



    <plugin name="ArduPilotPlugin"

      filename="ArduPilotPlugin">

      <!-- Port settings -->

      <fdm_addr>127.0.0.1</fdm_addr>

      <fdm_port_in>9002</fdm_port_in>

      <connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>

      <lock_step>1</lock_step>

      <have_32_channels>0</have_32_channels>



      <!-- Frame conventions

        Require by ArduPilot: change model and gazebo from XYZ to XY-Z coordinates

      -->

      <modelXYZToAirplaneXForwardZDown degrees="true">0 0 0 180 0 0</modelXYZToAirplaneXForwardZDown>

      <gazeboXYZToNED degrees="true">0 0 0 180 0 90</gazeboXYZToNED>



      <!-- Sensors -->

      <imuName>iris_with_standoffs::imu_link::imu_sensor</imuName>



      <!--

          incoming control command [0, 1]

          so offset it by 0 to get [0, 1]

          and divide max target by 1.

          offset = 0

          multiplier = 838 max rpm / 1 = 838

        -->

      <control channel="0">

        <jointName>iris_with_standoffs::rotor_1_joint</jointName>

        <useForce>1</useForce>

        <multiplier>838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



      <control channel="1">

        <jointName>iris_with_standoffs::rotor_2_joint</jointName>

        <useForce>1</useForce>

        <multiplier>-838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



      <control channel="2">

        <jointName>iris_with_standoffs::rotor_3_joint</jointName>

        <useForce>1</useForce>

        <multiplier>838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



      <control channel="3">

        <jointName>iris_with_standoffs::rotor_4_joint</jointName>

        <useForce>1</useForce>

        <multiplier>-838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



      <control channel="4">

        <jointName>iris_with_standoffs::rotor_5_joint</jointName>

        <useForce>1</useForce>

        <multiplier>838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



      <control channel="5">

        <jointName>iris_with_standoffs::rotor_6_joint</jointName>

        <useForce>1</useForce>

        <multiplier>-838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



      <control channel="6">

        <jointName>iris_with_standoffs::rotor_7_joint</jointName>

        <useForce>1</useForce>

        <multiplier>838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



      <control channel="7">

        <jointName>iris_with_standoffs::rotor_8_joint</jointName>

        <useForce>1</useForce>

        <multiplier>-838</multiplier>

        <offset>0</offset>

        <servo_min>1100</servo_min>

        <servo_max>1900</servo_max>

        <type>VELOCITY</type>

        <p_gain>0.20</p_gain>

        <i_gain>0</i_gain>

        <d_gain>0</d_gain>

        <i_max>0</i_max>

        <i_min>0</i_min>

        <cmd_max>2.5</cmd_max>

        <cmd_min>-2.5</cmd_min>

        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>

      </control>



    </plugin>



  </model>

</sdf>

Iris with standoffs

<?xml version="1.0"?>

<sdf version="1.9">

  <model name="iris_with_standoffs">

    <pose>0 0 0 0 0 0</pose>

    <link name="base_link">

      <velocity_decay>

        <linear>0.0</linear>

        <angular>0.0</angular>

      </velocity_decay>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>68</mass>

        <inertia>

          <ixx>14.73</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>13.83</iyy>

          <iyz>0</iyz>

          <izz>22.57</izz>

        </inertia>

      </inertial>

      <collision name="base_collision">

        <pose>0 0 -0.08 0 0 0</pose>

        <geometry>

          <box>

            <size>1.5 1.5 0.9</size>

          </box>

        </geometry>

        <surface>

          <contact>

            <ode>

              <max_vel>100.0</max_vel>

              <min_depth>0.001</min_depth>

            </ode>

          </contact>

          <friction>

            <ode>

              <mu>100000.0</mu>

              <mu2>100000.0</mu2>

            </ode>

          </friction>

        </surface>

      </collision>

      <visual name="base_visual">

        <geometry>

          <mesh>

            <uri>model://iris_with_standoffs/meshes/iris.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0.05 0.05 0.05</ambient>

          <diffuse>0.05 0.05 0.05</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>



      <visual name="front_left_leg_visual">

        <pose>23 0.22 -0.11 0 0 0</pose>

        <geometry>

          <cylinder>

            <radius>0.005</radius>

            <length>0.17</length>

          </cylinder>

        </geometry>

        <material>

          <ambient>0.05 0.05 0.05</ambient>

          <diffuse>0.05 0.05 0.05</diffuse>

          <specular>0.01 0.01 0.01 1.0</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <visual name="front_right_leg_visual">

        <pose>0.123 -0.22 -0.11 0 0 0</pose>

        <geometry>

          <cylinder>

            <radius>0.005</radius>

            <length>0.17</length>

          </cylinder>

        </geometry>

        <material>

          <ambient>0.05 0.05 0.05</ambient>

          <diffuse>0.05 0.05 0.05</diffuse>

          <specular>0.01 0.01 0.01 1.0</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <visual name="rear_left_leg_visual">

        <pose>-0.140 0.21 -0.11 0 0 0</pose>

        <geometry>

          <cylinder>

            <radius>0.005</radius>

            <length>0.17</length>

          </cylinder>

        </geometry>

        <material>

          <ambient>0.05 0.05 0.05</ambient>

          <diffuse>0.05 0.05 0.05</diffuse>

          <specular>0.01 0.01 0.01 1.0</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <visual name="rear_right_leg_visual">

        <pose>-0.140 -0.21 -0.11 0 0 0</pose>

        <geometry>

          <cylinder>

            <radius>0.005</radius>

            <length>0.17</length>

          </cylinder>

        </geometry>

        <material>

          <ambient>0.05 0.05 0.05</ambient>

          <diffuse>0.05 0.05 0.05</diffuse>

          <specular>0.01 0.01 0.01 1.0</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

    </link>

    <link name="imu_link">

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.15</mass>

        <inertia>

          <ixx>0.00001</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.00002</iyy>

          <iyz>0</iyz>

          <izz>0.00002</izz>

        </inertia>

      </inertial>

      <sensor name="imu_sensor" type="imu">

        <pose degrees="true">0 0 0 180 0 0</pose>

        <always_on>1</always_on>

        <update_rate>1000.0</update_rate>

      </sensor>

    </link>

    <joint name="imu_joint" type="revolute">

      <child>imu_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>0</lower>

          <upper>0</upper>

          <effort>0</effort>

          <velocity>0</velocity>

        </limit>

        <dynamics>

          <damping>1.0</damping>

        </dynamics>

      </axis>

    </joint>

    <link name="rotor_1_link">

      <pose>0.13 -0.22 0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_ccw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 0 1</ambient>

          <diffuse>0 0 1</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_1_joint" type="revolute">

      <child>rotor_1_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>

    <link name="rotor_2_link">

      <pose>0.13 0.22 0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_cw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 1 0</ambient>

          <diffuse>0 1 0</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_2_joint" type="revolute">

      <child>rotor_2_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>

    <link name="rotor_3_link">

      <pose>-0.13 0.2 0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_ccw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 0 1</ambient>

          <diffuse>0 0 1</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_3_joint" type="revolute">

      <child>rotor_3_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>

    <link name="rotor_4_link">

      <pose>-0.13 -0.2 0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_cw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 1 0</ambient>

          <diffuse>0 1 0</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_4_joint" type="revolute">

      <child>rotor_4_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>



    <link name="rotor_5_link">

      <pose>0.13 0.22 -0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_ccw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 0 1</ambient>

          <diffuse>0 0 1</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_5_joint" type="revolute">

      <child>rotor_5_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>

    <link name="rotor_6_link">

      <pose>0.13 -0.22 -0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_cw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 1 0</ambient>

          <diffuse>0 1 0</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_6_joint" type="revolute">

      <child>rotor_6_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>

    <link name="rotor_7_link">

      <pose>-0.13 -0.2 -0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_ccw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 0 1</ambient>

          <diffuse>0 0 1</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_7_joint" type="revolute">

      <child>rotor_7_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>

    <link name="rotor_8_link">

      <pose>-0.13 0.2 -0.023 0 0 0</pose>

      <inertial>

        <pose>0 0 0 0 0 0</pose>

        <mass>0.2</mass>

        <inertia>

          <ixx>9.75e-06</ixx>

          <ixy>0</ixy>

          <ixz>0</ixz>

          <iyy>0.000166704</iyy>

          <iyz>0</iyz>

          <izz>0.000167604</izz>

        </inertia>

      </inertial>

      <collision name="collision">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <cylinder>

            <length>0.005</length>

            <radius>0.46</radius>

          </cylinder>

        </geometry>

        <surface>

          <contact>

            <ode/>

          </contact>

          <friction>

            <ode/>

          </friction>

        </surface>

      </collision>

      <visual name="visual">

        <pose>0 0 0 0 0 0</pose>

        <geometry>

          <mesh>

            <scale>1 1 1</scale>

            <uri>model://iris_with_standoffs/meshes/iris_prop_cw.dae</uri>

          </mesh>

        </geometry>

        <material>

          <ambient>0 1 0</ambient>

          <diffuse>0 1 0</diffuse>

          <specular>1 1 1 1</specular>

          <pbr>

            <metal>

              <metalness>0.5</metalness>

              <roughness>0.5</roughness>

            </metal>

          </pbr>

        </material>

      </visual>

      <gravity>1</gravity>

      <velocity_decay/>

      <self_collide>0</self_collide>

    </link>

    <joint name="rotor_8_joint" type="revolute">

      <child>rotor_8_link</child>

      <parent>base_link</parent>

      <axis>

        <xyz>0 0 1</xyz>

        <limit>

          <lower>-1e+16</lower>

          <upper>1e+16</upper>

        </limit>

        <dynamics>

          <damping>0.004</damping>

        </dynamics>

      </axis>

      <physics>

        <ode>

          <implicit_spring_damper>1</implicit_spring_damper>

        </ode>

      </physics>

    </joint>



  </model>

</sdf>

Hi @rhys , any news?