From e0c4785b2ac26d97045c1c3d996e32618c43d1bd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 18 Oct 2013 10:41:07 +0900 Subject: [PATCH] Copter: OctaQuad H-frame support --- libraries/AP_Motors/AP_MotorsOctaQuad.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsOctaQuad.cpp b/libraries/AP_Motors/AP_MotorsOctaQuad.cpp index 20be604603..6cfe0c0cb6 100644 --- a/libraries/AP_Motors/AP_MotorsOctaQuad.cpp +++ b/libraries/AP_Motors/AP_MotorsOctaQuad.cpp @@ -39,6 +39,16 @@ void AP_MotorsOctaQuad::setup_motors() add_motor(AP_MOTORS_MOT_6, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); add_motor(AP_MOTORS_MOT_7, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); add_motor(AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); + }else if( _flags.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, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7); + add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); + add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); + add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8); + add_motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); + add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); + add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); }else{ // X frame set-up add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);