From 733b89cf3ca82bd29900dae63c2975a77f5fb896 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 4 Feb 2016 20:46:56 +0900 Subject: [PATCH] AP_MotorsHexa: call noramlise_rpy_factors in motor setup --- libraries/AP_Motors/AP_MotorsHexa.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsHexa.cpp b/libraries/AP_Motors/AP_MotorsHexa.cpp index a5f2d62b8f..0e55c13d28 100644 --- a/libraries/AP_Motors/AP_MotorsHexa.cpp +++ b/libraries/AP_Motors/AP_MotorsHexa.cpp @@ -46,4 +46,7 @@ void AP_MotorsHexa::setup_motors() add_motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); } + + // normalise factors to magnitude 0.5 + normalise_rpy_factors(); }