mirror of https://github.com/ArduPilot/ardupilot
Copter: add support for H-quad frame
H-quads are like X quads but the motors spin in the opposite direction. Having the motors reversed seems to help with yaw authority because of the slight flex in bodies
This commit is contained in:
parent
647a93e78e
commit
1cfd5900a8
|
@ -394,7 +394,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @Param: FRAME
|
||||
// @DisplayName: Frame Orientation (+, X or V)
|
||||
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
|
||||
// @Values: 0:Plus, 1:X, 2:V
|
||||
// @Values: 0:Plus, 1:X, 2:V, 3:H
|
||||
// @User: Standard
|
||||
// @Range: 0 32767
|
||||
GSCALAR(frame_orientation, "FRAME", FRAME_ORIENTATION),
|
||||
|
|
|
@ -24,10 +24,17 @@ void AP_MotorsQuad::setup_motors()
|
|||
add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
|
||||
add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
|
||||
}else if( _frame_orientation == AP_MOTORS_V_FRAME ) {
|
||||
// V frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 45, 0.7981, 1);
|
||||
add_motor(AP_MOTORS_MOT_2, -135, 1.0000, 3);
|
||||
add_motor(AP_MOTORS_MOT_3, -45, -0.7981, 4);
|
||||
add_motor(AP_MOTORS_MOT_4, 135, -1.0000, 2);
|
||||
}else if( _frame_orientation == AP_MOTORS_H_FRAME ) {
|
||||
// H frame set-up - same as X but motors spin in opposite directions
|
||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
|
||||
add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
|
||||
add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
|
||||
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
|
||||
}else{
|
||||
// X frame set-up
|
||||
add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
|
||||
|
|
|
@ -35,6 +35,7 @@
|
|||
#define AP_MOTORS_PLUS_FRAME 0
|
||||
#define AP_MOTORS_X_FRAME 1
|
||||
#define AP_MOTORS_V_FRAME 2
|
||||
#define AP_MOTORS_H_FRAME 3 // same as X frame but motors spin in opposite direction
|
||||
|
||||
// motor update rate
|
||||
#define AP_MOTORS_SPEED_DEFAULT 490
|
||||
|
|
Loading…
Reference in New Issue