mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: fix frame-type enum for Y6B
Also remove unused NEW_PLUS
This commit is contained in:
parent
e31d6d051d
commit
bdfb12123f
|
@ -578,7 +578,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||
|
||||
case MOTOR_FRAME_Y6:
|
||||
switch (frame_type) {
|
||||
case MOTOR_FRAME_TYPE_NEW_PLUS:
|
||||
case MOTOR_FRAME_TYPE_Y6B:
|
||||
// Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise
|
||||
add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
|
||||
add_motor_raw(AP_MOTORS_MOT_2, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
|
||||
|
|
|
@ -44,8 +44,7 @@ public:
|
|||
MOTOR_FRAME_TYPE_H = 3,
|
||||
MOTOR_FRAME_TYPE_VTAIL = 4,
|
||||
MOTOR_FRAME_TYPE_ATAIL = 5,
|
||||
MOTOR_FRAME_TYPE_Y6B = 6,
|
||||
MOTOR_FRAME_TYPE_NEW_PLUS = 10
|
||||
MOTOR_FRAME_TYPE_Y6B = 10
|
||||
};
|
||||
|
||||
// Constructor
|
||||
|
|
Loading…
Reference in New Issue