Coaxial octocopter Gazebo simulation problems

Hi,

I’m trying to create a coaxial octocopter for a research project. I’m trying start start out with creating a very simple model to fly in a Gazebo simulation, but I have some problems, since I’m not that experienced with either PX4 or Gazebo. I have managed to load the simple model into Gazebo and have 8 motors that all spins, but as soon as I try to takeoff the drone will flip over. I’m using version 1.13.0 of PX4.

I’m using the following files to try and create the drone, if somebody wants to replicate it. Let me know if anything is missing. Most of them was modified from other code I have found, so any help in improvements in them are appreciated :slight_smile:

The mixer file

# Octo coaxial

R: 8c

The geometry file located in init.d-posix being used.

#!/bin/sh
#
# @name Generic 10" Octo coaxial geometry
#
# @type Octorotor Coaxial
# @class Copter
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
# @output MAIN5 motor 5
# @output MAIN6 motor 6
# @output MAIN7 motor 7
# @output MAIN8 motor 8
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
# @board bitcraze_crazyflie exclude
#

. ${R}etc/init.d/rc.mc_defaults

set MIXER octo_cox

set PWM_OUT 12345678

The SDF file being used:


<?xml version='1.0'?>
<sdf version='1.6'>
  <model name='octo_cox'>
    <!--Drone body -->
    <link name='base_link'>
      <pose>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>6</mass>
        <inertia>
          <ixx>0.762625</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.762625</iyy>
          <iyz>0</iyz>
          <izz>1.369</izz>
        </inertia>
      </inertial>
      <collision name='base_link_inertia_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.74 0.74 0.25</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_inertia_visual'>
        <pose>0 0 0.125 1.57 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.3 0.3 0.3</scale>
            <uri>model://octo_cox/meshes/Part1.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <link name='/imu_link'>
      <pose>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.015</mass>
        <inertia>
          <ixx>1e-05</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1e-05</iyy>
          <iyz>0</iyz>
          <izz>1e-05</izz>
        </inertia>
      </inertial>
    </link>
    <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>

    <!-- Rotor 0 (CCW) -->
    <link name='rotor_0'>
      <pose>0.520429 -0.435000 0.220 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</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 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_ccw.dae</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/>
    </link>
    <joint name='rotor_0_joint' type='revolute'>
      <child>rotor_0</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>

    <!-- Rotor 1 (CW) -->
    <link name='rotor_1'>
	<pose>0.550429 0.535000 0.220 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</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 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_1_joint' type='revolute'>
      <child>rotor_1</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>

    <!-- Rotor 2 (CCW) -->
    <link name='rotor_2'>
      <pose>-0.40 0.535000 0.220 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</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 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_ccw.dae</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/>
    </link>
    <joint name='rotor_2_joint' type='revolute'>
      <child>rotor_2</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>

    <!-- Rotor 3 (CW) -->
    <link name='rotor_3'>
      <pose>-0.350429 -0.405000 0.220 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</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>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </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>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>


    <!-- Rotor 4 (CCW) -->
    <link name='rotor_4'>
      <pose>0.550429 0.535000 0.120 0 -0 0</pose>
	
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</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 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_ccw.dae</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/>
    </link>
    <joint name='rotor_4_joint' type='revolute'>
      <child>rotor_4</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>

    <!-- Rotor 5 (CW) -->
    <link name='rotor_5'>
      <pose>0.520429 -0.435000 0.120 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</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 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_5_joint' type='revolute'>
      <child>rotor_5</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
<!-- Rotor 6 (CCW) -->
    <link name='rotor_6'>
      <pose>-0.350429 -0.405000 0.120 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_6_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_6_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_ccw.dae</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/>
    </link>
    <joint name='rotor_6_joint' type='revolute'>
      <child>rotor_6</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
<!-- Rotor 7 (CW) -->
    <link name='rotor_7'>
	<pose>-0.40 0.535000 0.120 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_7_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_7_visual'>
      <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1.5 1.5 1.5</scale>
            <uri>model://sdu_description/meshes/prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_7_joint' type='revolute'>
      <child>rotor_7</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
      <robotNamespace/>
      <linkName>base_link</linkName>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
        <plugin name='motor_model_0' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_0_joint</jointName>
          <linkName>rotor_0</linkName>
          <turningDirection>ccw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</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='motor_model_1' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_1_joint</jointName>
          <linkName>rotor_1</linkName>
          <turningDirection>cw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</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='motor_model_2' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_2_joint</jointName>
          <linkName>rotor_2</linkName>
          <turningDirection>ccw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</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='motor_model_3' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_3_joint</jointName>
          <linkName>rotor_3</linkName>
          <turningDirection>cw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</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='motor_model_4' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_4_joint</jointName>
          <linkName>rotor_4</linkName>
          <turningDirection>ccw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</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='motor_model_5' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_5_joint</jointName>
          <linkName>rotor_5</linkName>
          <turningDirection>cw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</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='motor_model_6' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_6_joint</jointName>
          <linkName>rotor_6</linkName>
          <turningDirection>ccw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</maxRotVelocity>
          <motorConstant>8.54858e-06</motorConstant>
          <momentConstant>0.06</momentConstant>
          <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
          <motorNumber>6</motorNumber>
          <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
          <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
          <motorSpeedPubTopic>/motor_speed/6</motorSpeedPubTopic>
          <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
        </plugin>
<plugin name='motor_model_7' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_7_joint</jointName>
          <linkName>rotor_7</linkName>
          <turningDirection>cw</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</maxRotVelocity>
          <motorConstant>8.54858e-06</motorConstant>
          <momentConstant>0.06</momentConstant>
          <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
          <motorNumber>7</motorNumber>
          <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
          <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
          <motorSpeedPubTopic>/motor_speed/7</motorSpeedPubTopic>
          <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
        </plugin>
    <model name='gps0'>
      <link name='link'>
        <pose>0 0 0.125 0 -0 0</pose>
        <inertial>
          <pose>0 0 0 0 -0 0</pose>
          <mass>0.01</mass>
          <inertia>
            <ixx>2.1733e-06</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>2.1733e-06</iyy>
            <iyz>0</iyz>
            <izz>1.8e-07</izz>
          </inertia>
        </inertial>
        <visual name='visual'>
          <geometry>
            <cylinder>
              <radius>0.01</radius>
              <length>0.002</length>
            </cylinder>
          </geometry>
          <material>
            <script>
              <name>Gazebo/Black</name>
              <uri>__default__</uri>
            </script>
          </material>
        </visual>
        <sensor name='gps' type='gps'>
          <pose>0 0 0 0 -0 0</pose>
          <plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'>
            <robotNamespace/>
            <gpsNoise>1</gpsNoise>
            <gpsXYRandomWalk>2.0</gpsXYRandomWalk>
            <gpsZRandomWalk>4.0</gpsZRandomWalk>
            <gpsXYNoiseDensity>0.0002</gpsXYNoiseDensity>
            <gpsZNoiseDensity>0.0004</gpsZNoiseDensity>
            <gpsVXYNoiseDensity>0.2</gpsVXYNoiseDensity>
            <gpsVZNoiseDensity>0.4</gpsVZNoiseDensity>
          </plugin>
        </sensor>
      </link>
    </model>
    <joint name='gps0_joint' type='fixed'>
      <parent>base_link</parent>
      <child>gps0::link</child>
    </joint>
    <plugin name='groundtruth_plugin' filename='libgazebo_groundtruth_plugin.so'>
      <robotNamespace/>
    </plugin>
    <plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
      <robotNamespace/>
      <pubRate>20</pubRate>
      <noiseDensity>0.0004</noiseDensity>
      <randomWalk>6.4e-06</randomWalk>
      <biasCorrelationTime>600</biasCorrelationTime>
      <magTopic>/mag</magTopic>
    </plugin>
    <plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
      <robotNamespace/>
      <pubRate>10</pubRate>
      <baroTopic>/baro</baroTopic>
    </plugin>

    <plugin name='parachute_plugin' filename='libgazebo_parachute_plugin.so'>
      <robotNamespace/>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>6</motorNumber>
    </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_udp_port>14560</mavlink_udp_port>
      <mavlink_tcp_port>4560</mavlink_tcp_port>
      <serialEnabled>false</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>0</hil_state_level>
      <vehicle_is_tailsitter>0</vehicle_is_tailsitter>
      <send_vision_estimation>1</send_vision_estimation>
      <send_odometry>0</send_odometry>
      <enable_lockstep>1</enable_lockstep>
      <use_tcp>1</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>
          <joint_name>rotor_0_joint</joint_name>
        </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>
          <joint_name>rotor_1_joint</joint_name>
        </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>
          <joint_name>rotor_2_joint</joint_name>
        </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>
          <joint_name>rotor_3_joint</joint_name>
        </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>
          <joint_name>rotor_4_joint</joint_name>
        </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>
          <joint_name>rotor_5_joint</joint_name>
        </channel>
	<channel name="rotor6">
          <input_index>6</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>
          <joint_name>rotor_6_joint</joint_name>
        </channel>
	<channel name="rotor7">
          <input_index>7</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>
          <joint_name>rotor_7_joint</joint_name>
        </channel>
        <channel name='aux1'>
          <input_index>8</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</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>
    <plugin name='gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
      <robotNamespace></robotNamespace>
      <linkName>/imu_link</linkName>
      <imuTopic>/imu</imuTopic>
      <gyroscopeNoiseDensity>0.0003394</gyroscopeNoiseDensity>
      <gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
      <gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
      <gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
      <accelerometerNoiseDensity>0.004</accelerometerNoiseDensity>
      <accelerometerRandomWalk>0.006</accelerometerRandomWalk>
      <accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
      <accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
    </plugin>

</model>
</sdf>

Managed to solve it simply by moving the propellers further away from the center. The reason for this is that the geometry file says the propellers is located 0.7 meters away from the center, so moving the that far out made it fly.

Hi Mr_Madsen, I have questions about what you said "the geometry file says the propellers is located 0.7 meters away from the center’
What I’m confused about is the value of 0.7 is from the octo_cox.toml ?? and you modify your Rotor link pose ?? Is it correct?

yes, but later found out that I also had the MAV_type parameter to quad instead of octo, which gave me some problems.

Hello,
I am also working on using a coaxial octocopter model on gazebo and I have a problem on yaw control.
When all 8 motor are spinning the vehicle does not respond to yaw commands but when I disable bottom motors through the mixer the vehicle yaws without an issue.

Have you encountered this problem while working on your model and if so how you managed to solve it?

Hi,

No, I never got any problems with yaw control, when I created my coaxial simulation. Have you made sure the motors rotate in the correct orientation, similar to how the airframe configuration is setup?

Yeah, I figured the problem was not related to coaxial configuration. Apperently it was a know issue about VTOLs with multi pusher rotors.
Thanks

1 Like

I am facing the same issue with my simulation. So instead of changing the .sdf file, I created a new custom geometry file named octa_cox_custom.toml and used that in the airframe. But still, I am facing the same issue. Can someone help me? Thanks in advance.

did you find the solution for the same. because i am also getting the same error and i am using xplane 12 as a simulator for my work… i created the geometry file (.toml). but still i am getting the flipping error…