Rotors stop spinning in PX4 SITL simulation in Gazebo for custom model

Hi

I am simulating a Custom SITL model in PX4-Autopilot. I git clone https://github.com/PX4/PX4-Autopilot.git in my Linux computer (Ubuntu 20.04 with ROS Noetic).

I follow the instructions here to model a custom model in the SITL software (link: https://discuss.px4.io/t/create-custom-model-for-sitl/6700).

I create the hexaflat.sdf, hexaflat.world, model.config based on the typhon_h480 model available in the PX4 GitHub. Also, I create the airframe file 3012_hexaflat based on the tyhpoon_h480 as well.

I am able to run the simulation in gazebo with: make px4_sitl gazebo_hexaflat and the model appears in the simulator. When I input the command in the px4 terminal commander takeoff the model starts lifting, but some motors stop spinning. The model tilts and falls over.
Is like the same issue in this post:PX4-SITL with custom URDF model, drone crash after take off but I am using an sdf file.

I do not know why it is happening since I copy the typhoon files and I am able to fly the Typhoon model with commander takeoff.

I also add the hexaflat.sdf file.

<!-- DO NOT EDIT: Generated from iris.sdf.jinja -->
<sdf version='1.6'>
  <model name='hexaflat'>
    <link name='base_link'>
      <pose>0 0 0 0 0 0</pose>
      <inertial>
        <pose>0.001005 0 -0.0090035 0 0 0</pose>
        <mass>1.7971</mass>
        <inertia>
          <ixx>0.0244</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0422</iyy>
          <iyz>0</iyz>
          <izz>0.0235</izz>
        </inertia>
      </inertial>
      <collision name='base_link_collision'>
        <pose>0 0 0.0 0 0 0</pose>
        <geometry>
          <box>
            <size>0.6 0.6 0.38</size>
          </box>
        </geometry>
        <surface>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <max_vel>0</max_vel>
            </ode>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='base_link_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://hexaflat/meshes/base_link.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>



    <include>
      <uri>model://imu</uri>
      <pose relative_to='base_link'>0 0 0.125 0 0 0</pose>
      <name>imu</name>
    </include>
    <joint name='imu_joint' type='revolute'>
      <child>imu::link</child>
      <parent>base_link</parent>
      <axis>
        <xyz>1 0 0</xyz>
        <limit>
          <lower>0</lower>
          <upper>0</upper>
          <effort>0</effort>
          <velocity>0</velocity>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>



    <link name='rotor_3'>
      <pose >0.13 -0.22 0.0325 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.007</mass>
        <inertia>
          <ixx>0.000014</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000014</iyy>
          <iyz>0</iyz>
          <izz>0</izz>
        </inertia>
      </inertial>
      <collision name='rotor_3_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_3_visual'>
        <pose relative_to='rotor_3'>0 -0.1016 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.0009 0.0009 0.0009</scale>
            <uri>model://hexaflat/meshes/prop_ccw_hexaflat.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Green</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='rotor_3_joint' type='revolute'>
      <child>rotor_3</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
          <effort>10</effort>
          <velocity>-1</velocity>
        </limit>
        <dynamics>
          <damping>0.005</damping>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>



    <link name='rotor_0'>
      <pose>0.25 0 0.0325 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.007</mass>
        <inertia>
          <ixx>0.000014</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000014</iyy>
          <iyz>0</iyz>
          <izz>0</izz>
        </inertia>
      </inertial>
      <collision name='rotor_0_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_0_visual'>
        <pose>0 -0.1016 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.0009 0.0009 0.0009</scale>
            <uri>model://hexaflat/meshes/prop_cw_hexaflat.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Orange</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='rotor_0_joint' type='revolute'>
      <pose relative_to='rotor_0'>0 0 0 0 0 0</pose>
      <child>rotor_0</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
          <effort>10</effort>
          <velocity>-1</velocity>
        </limit>
        <dynamics>
          <damping>0.005</damping>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>



    <link name='rotor_4'>
      <pose>0.13 0.22 0.0325 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.007</mass>
        <inertia>
          <ixx>0.000014</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000014</iyy>
          <iyz>0</iyz>
          <izz>0</izz>
        </inertia>
      </inertial>
      <collision name='rotor_4_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_4_visual'>
        <pose>0 -0.1016 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.0009 0.0009 0.0009</scale>
            <uri>model://hexaflat/meshes/prop_ccw_hexaflat.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Red</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='rotor_4_joint' type='revolute'>
      <pose relative_to='rotor_4'>0 0 0 0 0 0</pose>
      <child>rotor_4</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
          <effort>10</effort>
          <velocity>-1</velocity>
        </limit>
        <dynamics>
          <damping>0.005</damping>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>



    <link name='rotor_1'>
      <pose>-0.25 0 0.0325 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.007</mass>
        <inertia>
          <ixx>0.000014</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000014</iyy>
          <iyz>0</iyz>
          <izz>0</izz>
        </inertia>
      </inertial>
      <collision name='rotor_1_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_1_visual'>
        <pose>0 -0.1016 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.0009 0.0009 0.0009</scale>
            <uri>model://hexaflat/meshes/prop_ccw_hexaflat.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Purple</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='rotor_1_joint' type='revolute'>
      <pose relative_to='rotor_1'>0 0 0 0 0 0</pose>
      <child>rotor_1</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
          <effort>10</effort>
          <velocity>-1</velocity>
        </limit>
        <dynamics>
          <damping>0.005</damping>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>



    <link name='rotor_5'>
      <pose>-0.13 -0.22 0.0325 0 0 0.75</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.007</mass>
        <inertia>
          <ixx>0.000014</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000014</iyy>
          <iyz>0</iyz>
          <izz>0</izz>
        </inertia>
      </inertial>
      <collision name='rotor_5_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_5_visual'>
        <pose>0 -0.1016 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.0009 0.0009 0.0009</scale>
            <uri>model://hexaflat/meshes/prop_cw_hexaflat.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/White</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='rotor_5_joint' type='revolute'>
      <pose relative_to='rotor_5'>0 0 0 0 0 0</pose>
      <child>rotor_5</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
          <effort>10</effort>
          <velocity>-1</velocity>
        </limit>
        <dynamics>
          <damping>0.005</damping>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>



    <link name='rotor_2'>
      <pose >-0.13 0.22 0.0325 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.007</mass>
        <inertia>
          <ixx>0.000014</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000014</iyy>
          <iyz>0</iyz>
          <izz>0</izz>
        </inertia>
      </inertial>
      <collision name='rotor_2_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_2_visual'>
        <pose>0 -0.1016 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.0009 0.0009 0.0009</scale>
            <uri>model://hexaflat/meshes/prop_cw_hexaflat.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Yellow</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='rotor_2_joint' type='revolute'>
      <pose relative_to='rotor_2'>0 0 0 0 0 0</pose>
      <child>rotor_2</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
          <effort>10</effort>
          <velocity>-1</velocity>
        </limit>
        <dynamics>
          <damping>0.005</damping>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>



    <include>
      <uri>model://gps</uri>
      <pose relative_to='base_link'>0.1 0 0.075 0 0 0</pose>
      <name>gps</name>
    </include>
    <joint name='gps_joint' type='fixed'>
      <child>gps::link</child>
      <parent>base_link</parent>
    </joint>



    <include>
      <uri>model://magnetometer</uri>
      <pose relative_to='base_link'>0 0.1 0.075 0 0 0</pose>
      <name>mag</name>
    </include>
    <joint name='mag_joint' type='fixed'>
      <child>mag::link</child>
      <parent>base_link</parent>
    </joint>



    <plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
      <robotNamespace></robotNamespace>
      <linkName>base_link</linkName>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>



    <plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_0_joint</jointName>
      <linkName>rotor_0</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1500</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>0</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>



    <plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_1_joint</jointName>
      <linkName>rotor_1</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1500</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>1</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>



    <plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_2_joint</jointName>
      <linkName>rotor_2</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1500</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>2</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>



    <plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_3_joint</jointName>
      <linkName>rotor_3</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1500</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>3</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>



    <plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_4_joint</jointName>
      <linkName>rotor_4</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1500</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>4</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/4</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>



    <plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace></robotNamespace>
      <jointName>rotor_5_joint</jointName>
      <linkName>rotor_5</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1500</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>5</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/5</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>



    <plugin name='groundtruth_plugin' filename='libgazebo_groundtruth_plugin.so'>
      <robotNamespace/>
    </plugin>



    <plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
      <robotNamespace/>
      <pubRate>50</pubRate>
      <baroTopic>/baro</baroTopic>
    </plugin>


    <plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
      <robotNamespace></robotNamespace>
      <imuSubTopic>/imu</imuSubTopic>
      <magSubTopic>/mag</magSubTopic>
      <baroSubTopic>/baro</baroSubTopic>
      <mavlink_addr>INADDR_ANY</mavlink_addr>
      <mavlink_tcp_port>4560</mavlink_tcp_port>
      <mavlink_udp_port>14560</mavlink_udp_port>
      <serialEnabled>0</serialEnabled>
      <serialDevice>/dev/ttyACM0</serialDevice>
      <baudRate>921600</baudRate>
      <qgc_addr>INADDR_ANY</qgc_addr>
      <qgc_udp_port>14550</qgc_udp_port>
      <sdk_addr>INADDR_ANY</sdk_addr>
      <sdk_udp_port>14540</sdk_udp_port>
      <hil_mode>0</hil_mode>
      <hil_state_level>false</hil_state_level>
      <enable_lockstep>true</enable_lockstep>
      <use_tcp>true</use_tcp>
      <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
      <control_channels>
        <channel name="rotor0">
          <input_index>0</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1500</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name="rotor1">
          <input_index>1</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1500</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name="rotor2">
          <input_index>2</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1500</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name="rotor3">
          <input_index>3</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1500</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name="rotor4">
          <input_index>4</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1500</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
       <channel name="rotor5">
          <input_index>5</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1500</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
      </control_channels>
    </plugin>
    <static>0</static>
  </model>
</sdf>

Can you guide on how to debug this sdf file or where is the problem here?

Thanks in advance!

Adán Márquez

1 Like

I’m facing the same problem—one of the six rotors isn’t working. Could anyone provide some advice?