|
|
|
@ -49,6 +49,15 @@ static Motor quad_bf_x_motors[] =
@@ -49,6 +49,15 @@ static Motor quad_bf_x_motors[] =
|
|
|
|
|
Motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4), |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
// motor order to match betaflight conventions, reversed direction
|
|
|
|
|
static Motor quad_bf_x_rev_motors[] = |
|
|
|
|
{ |
|
|
|
|
Motor(AP_MOTORS_MOT_1, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2), |
|
|
|
|
Motor(AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1), |
|
|
|
|
Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3), |
|
|
|
|
Motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 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[] = |
|
|
|
@ -190,6 +199,7 @@ static Frame supported_frames[] =
@@ -190,6 +199,7 @@ static Frame supported_frames[] =
|
|
|
|
|
Frame("quad", 4, quad_plus_motors), |
|
|
|
|
Frame("copter", 4, quad_plus_motors), |
|
|
|
|
Frame("x", 4, quad_x_motors), |
|
|
|
|
Frame("bfxrev", 4, quad_bf_x_rev_motors), |
|
|
|
|
Frame("bfx", 4, quad_bf_x_motors), |
|
|
|
|
Frame("djix", 4, quad_dji_x_motors), |
|
|
|
|
Frame("cwx", 4, quad_cw_x_motors), |
|
|
|
|