AP_MotorsY6: call normalise_rpy_factors in motor setup

This commit is contained in:
Leonard Hall 2016-02-04 20:49:40 +09:00 committed by Randy Mackay
parent 13ab3ecfea
commit 753b72b28c
1 changed files with 3 additions and 0 deletions

View File

@ -45,4 +45,7 @@ void AP_MotorsY6::setup_motors()
add_motor_raw(AP_MOTORS_MOT_5, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
add_motor_raw(AP_MOTORS_MOT_6, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
}
// normalise factors to magnitude 0.5
normalise_rpy_factors();
}