mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsY6: call normalise_rpy_factors in motor setup
This commit is contained in:
parent
13ab3ecfea
commit
753b72b28c
|
@ -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();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue