SITL: support 3 more X quad motor orders
- betaflight X - DJI X - clockwise X
This commit is contained in:
parent
9067e1099f
commit
40babb1172
@ -39,6 +39,35 @@ static Motor quad_x_motors[] =
|
||||
Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
};
|
||||
|
||||
// motor order to match betaflight conventions
|
||||
// See: https://fpvfrenzy.com/betaflight-motor-order/
|
||||
static Motor quad_bf_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW,1),
|
||||
Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW,3),
|
||||
Motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
};
|
||||
|
||||
// motor order to match DJI conventions
|
||||
// See: https://forum44.djicdn.com/data/attachment/forum/201711/26/172348bppvtt1ot1nrtp5j.jpg
|
||||
static Motor quad_dji_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
};
|
||||
|
||||
// motor order so that test order matches motor order ("clockwise X")
|
||||
static Motor quad_cw_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
|
||||
};
|
||||
|
||||
static Motor tiltquad_h_vectored_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1, -1, 0, 0, 7, 10, -90),
|
||||
@ -161,6 +190,9 @@ static Frame supported_frames[] =
|
||||
Frame("quad", 4, quad_plus_motors),
|
||||
Frame("copter", 4, quad_plus_motors),
|
||||
Frame("x", 4, quad_x_motors),
|
||||
Frame("bfx", 4, quad_bf_x_motors),
|
||||
Frame("djix", 4, quad_dji_x_motors),
|
||||
Frame("cwx", 4, quad_cw_x_motors),
|
||||
Frame("tilthvec", 4, tiltquad_h_vectored_motors),
|
||||
Frame("hexax", 6, hexax_motors),
|
||||
Frame("hexa", 6, hexa_motors),
|
||||
|
Loading…
Reference in New Issue
Block a user