Hexacopter keeps rotating while hovering in SITL

Hi there!
I’m trying to use a Hexacopter model which I’ve downloaded from Fuel and modified.
Once added the airframe, I can run a simulation in Gazebo Garden, but the copter keeps rotating with an oscillating yaw angle.
I can’t seem to understand why this is happening… Do you have any suggestions?

Here’s the modified sdf

<?xml version="1.0"?>
<sdf version="1.6">
    <model name="X4">
        <pose>0 0 0.121078 0 0 0</pose>

        <link name="base_link">
            <pose frame="">0 0 0 0 0 0</pose>

            <inertial>
                <pose frame="">0 0 0 0 0 0</pose>
                <mass>3.42</mass>
                <inertia>
                    <ixx>0.075</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>0.075</iyy>
                    <iyz>0</iyz>
                    <izz>0.148916</izz>
                </inertia>
            </inertial>
            <collision name="base_link_inertia_collision">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <box>
                        <size>0.3 0.3 0.25</size>
                    </box>
                </geometry>
            </collision>
            <visual name="base_link_inertia_visual">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <mesh>
                        <scale>1 1 1</scale>
                        <uri>model://X4/meshes/x4.dae</uri>
                    </mesh>
                </geometry>
            </visual>

            <gravity>1</gravity>
            <velocity_decay />
            <self_collide>0</self_collide>

            <sensor name="air_pressure_sensor" type="air_pressure">
                <always_on>1</always_on>
                <update_rate>50</update_rate>
                <air_pressure>
                    <pressure>
                        <noise type="gaussian">
                            <mean>0</mean>
                            <stddev>0.01</stddev>
                        </noise>
                    </pressure>
                </air_pressure>
            </sensor>
            <sensor name="imu_sensor" type="imu">
                <always_on>1</always_on>
                <update_rate>250</update_rate>
            </sensor>

        </link>
        
        <link name="rotor_0">
            <pose frame="">0.247 0.1506 0.028 0.087267 0 0.523599</pose>
            <inertial>
                <pose frame="">0 0 0 0 -0 0</pose>
                <mass>0.005</mass>
                <inertia>
                    <ixx>9.75e-07</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>8.13545e-05</iyy>
                    <iyz>0</iyz>
                    <izz>8.22545e-05</izz>
                </inertia>
            </inertial>
            <collision name="rotor_0_collision">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <cylinder>
                        <length>0.005</length>
                        <radius>0.1397</radius>
                    </cylinder>
                </geometry>
                <surface>
                    <contact>
                        <ode/>
                    </contact>
                    <friction>
                        <ode/>
                    </friction>
                </surface>
            </collision>
            <visual name="rotor_0_visual">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <mesh>
                        <scale>1 1 1</scale>
                        <uri>model://X4/meshes/neo11_propeller_ccw.dae</uri>
                    </mesh>
                </geometry>
                <material>
                    <diffuse>1 0 0 1</diffuse>
                    <script>
                        <name>Gazebo/Red</name>
                        <uri>file://media/materials/scripts/gazebo.material</uri>
                    </script>
                </material>
                <cast_shadows>0</cast_shadows>
            </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.043578 -0.075479 0.996195</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 filename="gz-sim-multicopter-motor-model-system"
            name="gz::sim::systems::MulticopterMotorModel">
            <jointName>rotor_0_joint</jointName>
            <linkName>rotor_0</linkName>
            <turningDirection>cw</turningDirection>
            <timeConstantUp>0.0125</timeConstantUp>
            <timeConstantDown>0.025</timeConstantDown>
            <maxRotVelocity>1000.0</maxRotVelocity>
            <motorConstant>8.54858e-06</motorConstant>
            <momentConstant>0.016</momentConstant>
            <commandSubTopic>command/motor_speed</commandSubTopic>
            <motorNumber>2</motorNumber>
            <rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
            <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
            <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
            <motorType>velocity</motorType>
        </plugin>
        
        <link name="rotor_1">
            <pose frame="">-0.00067 0.28929 0.028 0 -0.087267 0</pose>
            <inertial>
                <pose frame="">0 0 0 0 -0 0</pose>
                <mass>0.005</mass>
                <inertia>
                    <ixx>9.75e-07</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>8.13545e-05</iyy>
                    <iyz>0</iyz>
                    <izz>8.22545e-05</izz>
                </inertia>
            </inertial>
            <collision name="rotor_1_collision">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <cylinder>
                        <length>0.005</length>
                        <radius>0.1397</radius>
                    </cylinder>
                </geometry>
                <surface>
                    <contact>
                        <ode/>
                    </contact>
                    <friction>
                        <ode/>
                    </friction>
                </surface>
            </collision>
            <visual name="rotor_1_visual">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <mesh>
                        <scale>1 1 1</scale>
                        <uri>model://X4/meshes/neo11_propeller_cw.dae</uri>
                    </mesh>
                </geometry>
                <material>
                    <diffuse>0 0 1 1</diffuse>
                    <script>
                        <name>Gazebo/Blue</name>
                        <uri>file://media/materials/scripts/gazebo.material</uri>
                    </script>
                </material>
                <cast_shadows>0</cast_shadows>
            </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.087156 0 0.996195</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 filename="gz-sim-multicopter-motor-model-system"
            name="gz::sim::systems::MulticopterMotorModel">
            <jointName>rotor_1_joint</jointName>
            <linkName>rotor_1</linkName>
            <turningDirection>ccw</turningDirection>
            <timeConstantUp>0.0125</timeConstantUp>
            <timeConstantDown>0.025</timeConstantDown>
            <maxRotVelocity>1000.0</maxRotVelocity>
            <motorConstant>8.54858e-06</motorConstant>
            <momentConstant>0.016</momentConstant>
            <commandSubTopic>command/motor_speed</commandSubTopic>
            <motorNumber>1</motorNumber>
            <rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
            <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
            <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
            <motorType>velocity</motorType>
        </plugin>
        
        <link name="rotor_2">
            <pose frame="">-0.2501 0.1454 0.028 0.087267 -0 2.61799</pose>
            <inertial>
                <pose frame="">0 0 0 0 -0 0</pose>
                <mass>0.005</mass>
                <inertia>
                    <ixx>9.75e-07</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>8.13545e-05</iyy>
                    <iyz>0</iyz>
                    <izz>8.22545e-05</izz>
                </inertia>
            </inertial>
            <collision name="rotor_2_collision">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <cylinder>
                        <length>0.005</length>
                        <radius>0.1397</radius>
                    </cylinder>
                </geometry>
                <surface>
                    <contact>
                        <ode/>
                    </contact>
                    <friction>
                        <ode/>
                    </friction>
                </surface>
            </collision>
            <visual name="rotor_2_visual">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <mesh>
                        <scale>1 1 1</scale>
                        <uri>model://X4/meshes/neo11_propeller_ccw.dae</uri>
                    </mesh>
                </geometry>
                <material>
                    <diffuse>0 0 1 1</diffuse>
                    <script>
                        <name>Gazebo/Blue</name>
                        <uri>file://media/materials/scripts/gazebo.material</uri>
                    </script>
                </material>
                <cast_shadows>0</cast_shadows>
            </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.043578 0.075479 0.996195</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 filename="gz-sim-multicopter-motor-model-system"
            name="gz::sim::systems::MulticopterMotorModel">
            <jointName>rotor_2_joint</jointName>
            <linkName>rotor_2</linkName>
            <turningDirection>cw</turningDirection>
            <timeConstantUp>0.0125</timeConstantUp>
            <timeConstantDown>0.025</timeConstantDown>
            <maxRotVelocity>1000.0</maxRotVelocity>
            <motorConstant>8.54858e-06</motorConstant>
            <momentConstant>0.016</momentConstant>
            <commandSubTopic>command/motor_speed</commandSubTopic>
            <motorNumber>5</motorNumber>
            <rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
            <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
            <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
            <motorType>velocity</motorType>
        </plugin>
        
        <link name="rotor_3">
            <pose frame="">-0.2501 -0.1454 0.028 -0.087267 -0 -2.61799</pose>
            <inertial>
                <pose frame="">0 0 0 0 -0 0</pose>
                <mass>0.005</mass>
                <inertia>
                    <ixx>9.75e-07</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>8.13545e-05</iyy>
                    <iyz>0</iyz>
                    <izz>8.22545e-05</izz>
                </inertia>
            </inertial>
            <collision name="rotor_3_collision">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <cylinder>
                        <length>0.005</length>
                        <radius>0.1397</radius>
                    </cylinder>
                </geometry>
                <surface>
                    <contact>
                        <ode/>
                    </contact>
                    <friction>
                        <ode/>
                    </friction>
                </surface>
            </collision>
            <visual name="rotor_3_visual">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <mesh>
                        <scale>1 1 1</scale>
                        <uri>model://X4/meshes/neo11_propeller_cw.dae</uri>
                    </mesh>
                </geometry>
                <material>
                    <diffuse>0 0 1 1</diffuse>
                    <script>
                        <name>Gazebo/Blue</name>
                        <uri>file://media/materials/scripts/gazebo.material</uri>
                    </script>
                </material>
                <cast_shadows>0</cast_shadows>
            </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.043578 -0.075479 0.996195</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 filename="gz-sim-multicopter-motor-model-system"
            name="gz::sim::systems::MulticopterMotorModel">
            <jointName>rotor_3_joint</jointName>
            <linkName>rotor_3</linkName>
            <turningDirection>ccw</turningDirection>
            <timeConstantUp>0.0125</timeConstantUp>
            <timeConstantDown>0.025</timeConstantDown>
            <maxRotVelocity>1000.0</maxRotVelocity>
            <motorConstant>8.54858e-06</motorConstant>
            <momentConstant>0.016</momentConstant>
            <commandSubTopic>command/motor_speed</commandSubTopic>
            <motorNumber>3</motorNumber>
            <rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
            <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
            <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
            <motorType>velocity</motorType>
        </plugin>
        
        <link name="rotor_4">
            <pose frame="">-0.00067 -0.28929 0.028 -0 0.087267 -3.14159</pose>
            <inertial>
                <pose frame="">0 0 0 0 -0 0</pose>
                <mass>0.005</mass>
                <inertia>
                    <ixx>9.75e-07</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>8.13545e-05</iyy>
                    <iyz>0</iyz>
                    <izz>8.22545e-05</izz>
                </inertia>
            </inertial>
            <collision name="rotor_4_collision">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <cylinder>
                        <length>0.005</length>
                        <radius>0.1397</radius>
                    </cylinder>
                </geometry>
                <surface>
                    <contact>
                        <ode/>
                    </contact>
                    <friction>
                        <ode/>
                    </friction>
                </surface>
            </collision>
            <visual name="rotor_4_visual">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <mesh>
                        <scale>1 1 1</scale>
                        <uri>model://X4/meshes/neo11_propeller_ccw.dae</uri>
                    </mesh>
                </geometry>
                <material>
                    <diffuse>0 0 1 1</diffuse>
                    <script>
                        <name>Gazebo/Blue</name>
                        <uri>file://media/materials/scripts/gazebo.material</uri>
                    </script>
                </material>
                <cast_shadows>0</cast_shadows>
            </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.087156 -0 0.996195</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 filename="gz-sim-multicopter-motor-model-system"
            name="gz::sim::systems::MulticopterMotorModel">
            <jointName>rotor_4_joint</jointName>
            <linkName>rotor_4</linkName>
            <turningDirection>cw</turningDirection>
            <timeConstantUp>0.0125</timeConstantUp>
            <timeConstantDown>0.025</timeConstantDown>
            <maxRotVelocity>1000.0</maxRotVelocity>
            <motorConstant>8.54858e-06</motorConstant>
            <momentConstant>0.016</momentConstant>
            <commandSubTopic>command/motor_speed</commandSubTopic>
            <motorNumber>0</motorNumber>
            <rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
            <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
            <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
            <motorType>velocity</motorType>
        </plugin>
        
        <link name="rotor_5">
            <pose frame="">0.247 -0.1506 0.028 -0.087267 0 -0.523599</pose>
            <inertial>
                <pose frame="">0 0 0 0 -0 0</pose>
                <mass>0.005</mass>
                <inertia>
                    <ixx>9.75e-07</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>8.13545e-05</iyy>
                    <iyz>0</iyz>
                    <izz>8.22545e-05</izz>
                </inertia>
            </inertial>
            <collision name="rotor_5_collision">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <cylinder>
                        <length>0.005</length>
                        <radius>0.1397</radius>
                    </cylinder>
                </geometry>
                <surface>
                    <contact>
                        <ode/>
                    </contact>
                    <friction>
                        <ode/>
                    </friction>
                </surface>
            </collision>
            <visual name="rotor_5_visual">
                <pose frame="">0 0 0 0 -0 0</pose>
                <geometry>
                    <mesh>
                        <scale>1 1 1</scale>
                        <uri>model://X4/meshes/neo11_propeller_cw.dae</uri>
                    </mesh>
                </geometry>
                <material>
                    <diffuse>1 0 0 1</diffuse>
                    <script>
                        <name>Gazebo/Red</name>
                        <uri>file://media/materials/scripts/gazebo.material</uri>
                    </script>
                </material>
                <cast_shadows>0</cast_shadows>
            </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.043578 0.075479 0.996195</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 filename="gz-sim-multicopter-motor-model-system"
            name="gz::sim::systems::MulticopterMotorModel">
            <jointName>rotor_5_joint</jointName>
            <linkName>rotor_5</linkName>
            <turningDirection>ccw</turningDirection>
            <timeConstantUp>0.0125</timeConstantUp>
            <timeConstantDown>0.025</timeConstantDown>
            <maxRotVelocity>1000.0</maxRotVelocity>
            <motorConstant>8.54858e-06</motorConstant>
            <momentConstant>0.016</momentConstant>
            <commandSubTopic>command/motor_speed</commandSubTopic>
            <motorNumber>4</motorNumber>
            <rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
            <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
            <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
            <motorType>velocity</motorType>
        </plugin>
    </model>
</sdf>

and this is the airframe file

#!/bin/sh
#
# @name OpenRobotics X4
#
# @type Hexarotor x
#

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

PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=X4}

param set-default SIM_GZ_EN 1

param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1 

param set-default MAV_TYPE 13
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 6

# Rotors
# SDF and Airframe have different reference frames!
param set-default CA_ROTOR0_PX -0.00067
param set-default CA_ROTOR0_PY  0.28929
param set-default CA_ROTOR0_KM -0.05 # CW

param set-default CA_ROTOR1_PX -0.00067
param set-default CA_ROTOR1_PY -0.28929
param set-default CA_ROTOR1_KM  0.05 # CCW

param set-default CA_ROTOR2_PX  0.247
param set-default CA_ROTOR2_PY -0.1506
param set-default CA_ROTOR2_KM -0.05 # CW

param set-default CA_ROTOR3_PX -0.2501
param set-default CA_ROTOR3_PY  0.1454
param set-default CA_ROTOR3_KM  0.05 # CCW

param set-default CA_ROTOR4_PX  0.247
param set-default CA_ROTOR4_PY  0.1506
param set-default CA_ROTOR4_KM  0.05 # CCW

param set-default CA_ROTOR5_PX -0.2501
param set-default CA_ROTOR5_PY -0.1454
param set-default CA_ROTOR5_KM -0.05 # CW

# Set actuators to some functions
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_EC_FUNC3 103
param set-default SIM_GZ_EC_FUNC4 104
param set-default SIM_GZ_EC_FUNC5 105
param set-default SIM_GZ_EC_FUNC6 106

# Min-Max throttle values
param set-default SIM_GZ_EC_MIN1 150
param set-default SIM_GZ_EC_MIN2 150
param set-default SIM_GZ_EC_MIN3 150
param set-default SIM_GZ_EC_MIN4 150
param set-default SIM_GZ_EC_MIN5 150
param set-default SIM_GZ_EC_MIN6 150

param set-default SIM_GZ_EC_MAX1 1000
param set-default SIM_GZ_EC_MAX2 1000
param set-default SIM_GZ_EC_MAX3 1000
param set-default SIM_GZ_EC_MAX4 1000
param set-default SIM_GZ_EC_MAX5 1000
param set-default SIM_GZ_EC_MAX6 1000

# Throttle % needed to hover
param set-default MPC_THR_HOVER 0.60

In the sdf file all the rotors seem like have different roll pitch yaw angle. I am not sure if its on purpose. If not that might be the reason.

<link name="rotor_5">
            <pose frame="">0.247 -0.1506 0.028 -0.087267 0 -0.523599</pose>
<link name="rotor_4">
            <pose frame="">-0.00067 -0.28929 0.028 -0 0.087267 -3.14159</pose>
<link name="rotor_3">
            <pose frame="">-0.2501 -0.1454 0.028 -0.087267 -0 -2.61799</pose>

It might be a parameter thing have you tried running this drone with new build? (Delete the build in the PX4-Autopilot) and call this drone again in the cmd uploads new build.

Also can you share the log in the flight review. Maybe just bad pid tuning?

Here’s the log from a “normal” run as yesterday: https://logs.px4.io/plot_app?log=f045bfbc-34d2-423c-b8b5-23b4195702c5

I’ve tried adding the rotors’ orientation in the airframe, like this

param set-default CA_ROTOR0_PX -0.00067
param set-default CA_ROTOR0_PY  0.28929
param set-default CA_ROTOR0_PZ  0.028
param set-default CA_ROTOR0_AX  0.087267
param set-default CA_ROTOR0_AY  0
param set-default CA_ROTOR0_AZ  0.523599
param set-default CA_ROTOR0_KM -0.05 # CW

param set-default CA_ROTOR1_PX -0.00067
param set-default CA_ROTOR1_PY -0.28929
param set-default CA_ROTOR0_PZ  0.028
param set-default CA_ROTOR1_AX  0
param set-default CA_ROTOR1_AY -0.087267
param set-default CA_ROTOR1_AZ  0
param set-default CA_ROTOR1_KM  0.05 # CCW

param set-default CA_ROTOR2_PX  0.247
param set-default CA_ROTOR2_PY -0.1506
param set-default CA_ROTOR0_PZ  0.028
param set-default CA_ROTOR2_AX  0.087267
param set-default CA_ROTOR2_AY  0
param set-default CA_ROTOR2_AZ  2.61799
param set-default CA_ROTOR2_KM -0.05 # CW

param set-default CA_ROTOR3_PX -0.2501
param set-default CA_ROTOR3_PY  0.1454
param set-default CA_ROTOR0_PZ  0.028
param set-default CA_ROTOR3_AX -0.087267
param set-default CA_ROTOR3_AY  0
param set-default CA_ROTOR3_AZ -2.61799
param set-default CA_ROTOR3_KM  0.05 # CCW

param set-default CA_ROTOR4_PX  0.247
param set-default CA_ROTOR4_PY  0.1506
param set-default CA_ROTOR0_PZ  0.028
param set-default CA_ROTOR4_AX  0
param set-default CA_ROTOR4_AY  0.087267
param set-default CA_ROTOR4_AZ -3.14159
param set-default CA_ROTOR4_KM  0.05 # CCW

param set-default CA_ROTOR5_PX -0.2501
param set-default CA_ROTOR5_PY -0.1454
param set-default CA_ROTOR0_PZ  0.028
param set-default CA_ROTOR5_AX -0.087267
param set-default CA_ROTOR5_AY  0
param set-default CA_ROTOR5_AZ -0.523599
param set-default CA_ROTOR5_KM -0.05 # CW

but the copter then does not even lift: https://logs.px4.io/plot_app?log=d09a9fdf-eca9-4e4b-bfad-c90f2b2144c9

Have I used the wrong parameters?

Finally, I’ve tried a clear run but with no luck…

I changed the typhoon_h480’s rotors roll pitch yaw angle as same as yours in the sdf file. It flied well so your problem is not related to sdf file rotor orientation.
In the log file it seems it can’t follow yaw setpoint
;

Maybe you can try to change MC_YAWRATE and MC_YAW parameters for the yaw rate make MC_YAWRATE_I and MC_YAWRATE_D rates a 0 then start increasing the MC_YAWRATE_P gain check the log again then change the I and D as well. I am using version 1.12 i didn’t left any space in the virtualbox so i can’t get build in the 1.13 i am not able to test your model sorry.
You can try to change the airframe to typhoon_h480’s since its also hexacopter.
These are all what came to my mind so far. Update here how it goes when you have time gl.

oof, that’s somewhat difficult to get right…
I’ll try a bit, maybe applying Ziegler-Nichols or similar, then I think I’ll give up if I don’t succeed…
Thanks anyway!

I’ve found myself trying to approach this again, since I’d like to use this model for some project I have… Unfortunately I don’t seem to be able to find a good setup, as everything I do ends up in oscillations of varying amplitude…
If there’s some way to get “live” support from anyone, great, otherwise I think I’ll really give up on this