mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_MotorsHexa: call noramlise_rpy_factors in motor setup
This commit is contained in:
parent
8f8eb7e214
commit
733b89cf3c
@ -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();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user