AC_PosControl: remove default from set_alt_target_from_climb_rate

This commit is contained in:
Randy Mackay 2015-06-05 15:15:03 +09:00
parent 362a43c126
commit 6ea60aa662
1 changed files with 1 additions and 1 deletions

View File

@ -125,7 +125,7 @@ public:
/// actual position target will be moved no faster than the speed_down and speed_up
/// target will also be stopped if the motors hit their limits or leash length is exceeded
/// set force_descend to true during landing to allow target to move low enough to slow the motors
void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend = false);
void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend);
/// add_takeoff_climb_rate - adjusts alt target up or down using a climb rate in cm/s
/// should be called continuously (with dt set to be the expected time between calls)