|
|
|
@ -476,6 +476,15 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
@@ -476,6 +476,15 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|
|
|
|
add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); |
|
|
|
|
success = true; |
|
|
|
|
break; |
|
|
|
|
case MOTOR_FRAME_TYPE_H: |
|
|
|
|
add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); |
|
|
|
|
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
|
|
|
|
add_motor(AP_MOTORS_MOT_3, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); |
|
|
|
|
add_motor(AP_MOTORS_MOT_4, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); |
|
|
|
|
add_motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); |
|
|
|
|
add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); |
|
|
|
|
success = true; |
|
|
|
|
break; |
|
|
|
|
default: |
|
|
|
|
// hexa frame class does not support this frame type
|
|
|
|
|
break; |
|
|
|
@ -517,6 +526,17 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
@@ -517,6 +526,17 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|
|
|
|
add_motor_raw(AP_MOTORS_MOT_8, 0.5f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); |
|
|
|
|
success = true; |
|
|
|
|
break; |
|
|
|
|
case MOTOR_FRAME_TYPE_H: |
|
|
|
|
add_motor(AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); |
|
|
|
|
add_motor(AP_MOTORS_MOT_2, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); |
|
|
|
|
add_motor(AP_MOTORS_MOT_3, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); |
|
|
|
|
add_motor(AP_MOTORS_MOT_4, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); |
|
|
|
|
add_motor(AP_MOTORS_MOT_5, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8); |
|
|
|
|
add_motor(AP_MOTORS_MOT_6, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); |
|
|
|
|
add_motor(AP_MOTORS_MOT_7, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7); |
|
|
|
|
add_motor(AP_MOTORS_MOT_8, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); |
|
|
|
|
success = true; |
|
|
|
|
break; |
|
|
|
|
default: |
|
|
|
|
// octa frame class does not support this frame type
|
|
|
|
|
break; |
|
|
|
|