mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
Copter: add trapezoid frame type
We still need to properly define the motor mixing for the trapezoid frame in AP_MotorsQuad.cpp
This commit is contained in:
parent
dfb14d760b
commit
39ba406957
@ -23,6 +23,12 @@ void AP_MotorsQuad::setup_motors()
|
||||
add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_MOTOR_CCW, 4);
|
||||
add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_MOTOR_CW, 1);
|
||||
add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_MOTOR_CW, 3);
|
||||
}else if( _frame_orientation == AP_MOTORS_TRAPEZOID_FRAME ) {
|
||||
// To-Do correct motor mixing properly for trapezoidal frame
|
||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_MOTOR_CCW, 1);
|
||||
add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_MOTOR_CCW, 3);
|
||||
add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_MOTOR_CW, 4);
|
||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_MOTOR_CW, 2);
|
||||
}else{
|
||||
// X frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_MOTOR_CCW, 1);
|
||||
|
@ -32,9 +32,10 @@
|
||||
#define AP_MOTORS_APM2 2
|
||||
|
||||
// frame definitions
|
||||
#define AP_MOTORS_PLUS_FRAME 0
|
||||
#define AP_MOTORS_X_FRAME 1
|
||||
#define AP_MOTORS_V_FRAME 2
|
||||
#define AP_MOTORS_PLUS_FRAME 0
|
||||
#define AP_MOTORS_X_FRAME 1
|
||||
#define AP_MOTORS_V_FRAME 2
|
||||
#define AP_MOTORS_TRAPEZOID_FRAME 3
|
||||
|
||||
// motor update rate
|
||||
#define AP_MOTORS_SPEED_DEFAULT 490
|
||||
|
Loading…
Reference in New Issue
Block a user