Browse Source

AP_MotorsCoax: roll, pitch, yaw input in -1 to +1 range

mission-4.1.18
Leonard Hall 9 years ago committed by Randy Mackay
parent
commit
1a308c2eb8
  1. 6
      libraries/AP_Motors/AP_MotorsCoax.cpp

6
libraries/AP_Motors/AP_MotorsCoax.cpp

@ -200,9 +200,9 @@ void AP_MotorsCoax::output_armed_stabilizing() @@ -200,9 +200,9 @@ void AP_MotorsCoax::output_armed_stabilizing()
// apply voltage and air pressure compensation
// todo: we shouldn't need input reversing with servo reversing
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();
// assuming maximum actuator defection the maximum roll and pitch torque is approximately proportional to thrust

Loading…
Cancel
Save