mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 10:58:30 -04:00
AP_MotorsMatrix: roll, pitch, yaw input in -1 to +1 range
This commit is contained in:
parent
ae4e495698
commit
027284fba0
@ -176,9 +176,9 @@ void AP_MotorsMatrix::output_armed_stabilizing()
|
||||
float throttle_thrust_hover = get_hover_throttle_as_high_end_pct(); // throttle hover thrust value, 0.0 - 1.0
|
||||
|
||||
// apply voltage and air pressure compensation
|
||||
roll_thrust = get_roll_thrust() * get_compensation_gain();
|
||||
pitch_thrust = get_pitch_thrust() * get_compensation_gain();
|
||||
yaw_thrust = get_yaw_thrust() * get_compensation_gain();
|
||||
roll_thrust = _roll_in * get_compensation_gain();
|
||||
pitch_thrust = _pitch_in * get_compensation_gain();
|
||||
yaw_thrust = _yaw_in * get_compensation_gain();
|
||||
throttle_thrust = get_throttle() * get_compensation_gain();
|
||||
|
||||
// sanity check throttle is above zero and below current limited throttle
|
||||
|
Loading…
Reference in New Issue
Block a user