AP_MotorsHexa: call noramlise_rpy_factors in motor setup

This commit is contained in:
Leonard Hall 2016-02-04 20:46:56 +09:00 committed by Randy Mackay
parent 8f8eb7e214
commit 733b89cf3c

View File

@ -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();
}