Hi, i think you meant CAL_MAG0_ROT as Pitch 180 right? If the orientations are detected correctly during the compass calibration routine then your rotation parameters are most likely correct, especially if it works in ardupilot. I did notice after setting CAL_ACC2_PRIO and CAL_GYRO2_PRIO to High , the post filtered gyro and accel values do look better to me, and consistent with moments in your previous flights where the estimator had this imu selected, these are good inputs for the estimator to have in general. I’ve never personally used ardupilot, but i’m assuming you chose frame class as quad and frame type as 3, i did skim through ardupilot’s src code and it’s setup for this configuration looks more simple than the H-frame config in PX4:
snippet in ardupilot’s AP_MotorsMatrix.cpp:
I could be missing something but it looks like this is all ardupilot does.
The H-frame config for px4 that you chose looks to be vehicle-specific
possibly this:
this is what happens when you choose BetaFPV Beta75X 2S Brushless Whoop, Quadrotor H:
snippet from ROMFS/px4fmu_common/init.d/airframes/4041_beta75x:
@name BetaFPV Beta75X 2S Brushless Whoop
param set-default CBRK_SUPPLY_CHK 894281
param set-default IMU_GYRO_CUTOFF 100
par@namem set-default IMU_DGYRO_CUTOFF 60
param set-default MC_AIRMODE 2
param set-default MC_PITCHRATE_D 0.001
param set-default MC_PITCHRATE_I 0.5
param set-default MC_PITCHRATE_MAX 600
param set-default MC_PITCHRATE_P 0.075
param set-default MC_PITCH_P 6
param set-default MC_ROLLRATE_D 0.001
param set-default MC_ROLLRATE_I 0.4
param set-default MC_ROLLRATE_MAX 600
param set-default MC_ROLLRATE_P 0.075
param set-default MC_YAWRATE_I 0.3
param set-default MC_YAWRATE_MAX 400
param set-default MC_YAWRATE_P 0.12
param set-default MC_YAW_P 4
param set-default MPC_MANTHR_MIN 0
param set-default MPC_MAN_TILT_MAX 60
param set-default SYS_HAS_BARO 0
param set-default SYS_HAS_MAG 0
param set-default BAT1_N_CELLS 2
# Square quadrotor X with reverse turn direction
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 1
param set-default CA_ROTOR0_PY 1
param set-default CA_ROTOR0_KM -0.05
param set-default CA_ROTOR1_PX -1
param set-default CA_ROTOR1_PY -1
param set-default CA_ROTOR1_KM -0.05
param set-default CA_ROTOR2_PX 1
param set-default CA_ROTOR2_PY -1
param set-default CA_ROTOR3_PX -1
param set-default CA_ROTOR3_PY 1
param set-default PWM_MAIN_FUNC1 104
param set-default PWM_MAIN_FUNC2 101
param set-default PWM_MAIN_FUNC3 102
param set-default PWM_MAIN_FUNC4 103
But when I download your current parameters, it looks like you’ve already changed most of the parameters that the config defaults, I would compare your current param settings with the default params above. In your logs, your rate tracking does look bad, my new theory is that it’s likely bad tuning from an incorrect baseline configuration. It could explain why in some flights you got compass errors (when external compass was used), gnss fusion stopped, etc. Bad tuning would cause unpredictable motion that could spike ekf innovations and possibly result in that. This could also explain why ardupilot is fine, it’s baseline configuration for H-Frame looks to be much more simple, and your tuning from that point was correct. I think it might be worth to try starting from scratch (reset tuning parameters etc or even a complete reset). You could probably try quadrotor X configuration, and tune from there as this is what it does:
Square quadrotor X PX4 numbering
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 1
param set-default CA_ROTOR0_PY 1
param set-default CA_ROTOR1_PX -1
param set-default CA_ROTOR1_PY -1
param set-default CA_ROTOR2_PX 1
param set-default CA_ROTOR2_PY -1
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -1
param set-default CA_ROTOR3_PY 1
param set-default CA_ROTOR3_KM -0.05
you can probably copy the Betafpv H-Frame CA_ROTOR params if you need it.