Custom mixer matrix does not work in SITL

Hi,
I am running a copter in auto mission with 3-4 waypoints in SITL with mission planner. I am using a mixer for 6 rotors. I have got the matrix from [Multi-rotor motor mixing calculator].
add_motor_raw(AP_MOTORS_MOT_1, -0.5, -0.866, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); add_motor_raw(AP_MOTORS_MOT_2, -0.5, 0.866, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); add_motor_raw(AP_MOTORS_MOT_3, 0.5, -0.866, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); add_motor_raw(AP_MOTORS_MOT_4, 0.5, 0.866, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); add_motor_raw(AP_MOTORS_MOT_5, -1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); add_motor_raw(AP_MOTORS_MOT_6, 1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
I have added the generated commands via lua scripting. In the servo output section, I get the 6 green bars for first 6 servo outputs and the lua script is also running since I am getting the frame name in the messages tab of mission planner that I had set in the script. The frame class is Hexa and frame type is X. I have taken 1 for CCW and -1 for CW in yaw factors.
But the copter does not move in SITL and I get some compass errors. I discovered that the mixer values in arducopter code for HEXA-X is same as the one I mentioned above except for the fact that the motor numbering is different.

I know it is a bit lengthy, but can anyone please help me understand the issue?

Thanks,
Sayan

Just adding the commands in lua tells ArduCopter what the vehicle looks like, but it does not change the simulated vehicle. You need the simulated frame to match the one your defining. The simulated frames are here:

1 Like

Thanks Peter, I will try modifying this also. Just one query I need to modify this file only when I run SITL and not in real copter right (writing the Lua would be enough?)?

Right, on a real copter you don’t need the simulated frame because you have a real one.

1 Like

Thanks for clarifying!!!

Hi Pete,
I am trying to modify the “hexa_motors” array in the file.
`static Motor hexa_motors =
{

Motor(AP_MOTORS_MOT_1,   0, AP_MOTORS_MATRIX_YAW_FACTOR_CW,  1),
Motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
Motor(AP_MOTORS_MOT_3,-120, AP_MOTORS_MATRIX_YAW_FACTOR_CW,  5),
Motor(AP_MOTORS_MOT_4,  60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
Motor(AP_MOTORS_MOT_5, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6),
Motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW,  3)

};`

But how do I convert the roll and pitch factor in my custom mixer matrix to the angle that is the second argument in the “Motor” constructor. Is there any direct relationship (in mathematical equations) between them? Also the third argument in the ‘Motor’ constructor says the display sequence. How does this parameter change the flight dynamics? or will giving the value at any sequence work?

Can you please give some hints here?

Thanks,
Sayan