AP_Motors: Added Octo I frame
This commit is contained in:
parent
fc84995fb9
commit
7323a5da9d
@ -649,6 +649,16 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
add_motor_raw(AP_MOTORS_MOT_7, 1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
|
||||
add_motor_raw(AP_MOTORS_MOT_8, -1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
|
||||
break;
|
||||
case MOTOR_FRAME_TYPE_I:
|
||||
add_motor_raw(AP_MOTORS_MOT_1, 0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
|
||||
add_motor_raw(AP_MOTORS_MOT_2, -0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
|
||||
add_motor_raw(AP_MOTORS_MOT_3, 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
|
||||
add_motor_raw(AP_MOTORS_MOT_4, 0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
|
||||
add_motor_raw(AP_MOTORS_MOT_5, -0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
|
||||
add_motor_raw(AP_MOTORS_MOT_6, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
|
||||
add_motor_raw(AP_MOTORS_MOT_7, -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
|
||||
add_motor_raw(AP_MOTORS_MOT_8, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
|
||||
break;
|
||||
default:
|
||||
// octa frame class does not support this frame type
|
||||
success = false;
|
||||
|
@ -58,6 +58,7 @@ public:
|
||||
MOTOR_FRAME_TYPE_BF_X = 12, // X frame, betaflight ordering
|
||||
MOTOR_FRAME_TYPE_DJI_X = 13, // X frame, DJI ordering
|
||||
MOTOR_FRAME_TYPE_CW_X = 14, // X frame, clockwise ordering
|
||||
MOTOR_FRAME_TYPE_I = 15, // (sideways H) octo only
|
||||
};
|
||||
|
||||
// Constructor
|
||||
|
Loading…
Reference in New Issue
Block a user