Browse Source

Copter: bug fix for auto missions over 320m

get_throttle_althold_with_slew's target_alt parameter defined as int16_t
(instead of int32_t) meaning missions with altitudes >320m could wrap
around and become negative.
master
Randy Mackay 12 years ago
parent
commit
37040adfaa
  1. 2
      ArduCopter/Attitude.pde

2
ArduCopter/Attitude.pde

@ -1059,7 +1059,7 @@ get_throttle_althold(int32_t target_alt, int16_t min_climb_rate, int16_t max_cli @@ -1059,7 +1059,7 @@ get_throttle_althold(int32_t target_alt, int16_t min_climb_rate, int16_t max_cli
// get_throttle_althold_with_slew - altitude controller with slew to avoid step changes in altitude target
// calls normal althold controller which updates accel based throttle controller targets
static void
get_throttle_althold_with_slew(int16_t target_alt, int16_t min_climb_rate, int16_t max_climb_rate)
get_throttle_althold_with_slew(int32_t target_alt, int16_t min_climb_rate, int16_t max_climb_rate)
{
// limit target altitude change
controller_desired_alt += constrain(target_alt-controller_desired_alt, min_climb_rate*0.02f, max_climb_rate*0.02f);

Loading…
Cancel
Save