|
|
|
@ -517,6 +517,13 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
@@ -517,6 +517,13 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|
|
|
|
add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW,3); |
|
|
|
|
add_motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); |
|
|
|
|
break; |
|
|
|
|
case MOTOR_FRAME_TYPE_BF_X_REV: |
|
|
|
|
// betaflight quad X order, reversed motors
|
|
|
|
|
add_motor(AP_MOTORS_MOT_1, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
|
|
|
|
add_motor(AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
|
|
|
|
add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
|
|
|
|
add_motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
|
|
|
|
break; |
|
|
|
|
case MOTOR_FRAME_TYPE_DJI_X: |
|
|
|
|
// DJI quad X order
|
|
|
|
|
// see https://forum44.djicdn.com/data/attachment/forum/201711/26/172348bppvtt1ot1nrtp5j.jpg
|
|
|
|
|