mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: fixed typo in MotorsMatrixTS update for FF
This commit is contained in:
parent
fb790cadda
commit
2b3ced752b
|
@ -76,7 +76,7 @@ void AP_MotorsMatrixTS::output_armed_stabilizing()
|
|||
// apply voltage and air pressure compensation
|
||||
const float compensation_gain = get_compensation_gain(); // compensation for battery voltage and altitude
|
||||
roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
|
||||
pitch_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
|
||||
pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
|
||||
throttle_thrust = get_throttle() * compensation_gain;
|
||||
|
||||
// sanity check throttle is above zero and below current limited throttle
|
||||
|
|
Loading…
Reference in New Issue