mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: added quadplane frame type
this puts the motors on outputs 5 to 8, to leave the first 4 for the plane
This commit is contained in:
parent
22e25cc792
commit
b187a0c6eb
|
@ -88,6 +88,12 @@ void AP_MotorsQuad::setup_motors()
|
|||
add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
|
||||
add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
|
||||
add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
|
||||
} else if ( _flags.frame_orientation == AP_MOTORS_QUADPLANE ) {
|
||||
// quadplane frame set-up, X arrangement on motors 5 to 8
|
||||
add_motor(AP_MOTORS_MOT_5, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
|
||||
add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
|
||||
add_motor(AP_MOTORS_MOT_7, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
|
||||
add_motor(AP_MOTORS_MOT_8, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
|
||||
}else{
|
||||
// X frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
#define AP_MOTORS_NEW_X_FRAME 11
|
||||
#define AP_MOTORS_NEW_V_FRAME 12
|
||||
#define AP_MOTORS_NEW_H_FRAME 13 // same as X frame but motors spin in opposite direction
|
||||
#define AP_MOTORS_QUADPLANE 14 // motors on 5..8
|
||||
|
||||
// motor update rate
|
||||
#define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
|
||||
|
|
Loading…
Reference in New Issue