diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index 0d7a275d2c..e7e1ac1e18 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -225,7 +225,8 @@ bool Mode::stop_vehicle() } // estimate maximum vehicle speed (in m/s) -float Mode::calc_speed_max(float cruise_speed, float cruise_throttle) +// cruise_speed is in m/s, cruise_throttle should be in the range -1 to +1 +float Mode::calc_speed_max(float cruise_speed, float cruise_throttle) const { float speed_max; diff --git a/APMrover2/mode.h b/APMrover2/mode.h index a016f19c15..e42f7bed7f 100644 --- a/APMrover2/mode.h +++ b/APMrover2/mode.h @@ -121,7 +121,8 @@ protected: bool stop_vehicle(); // estimate maximum vehicle speed (in m/s) - float calc_speed_max(float cruise_speed, float cruise_throttle); + // cruise_speed is in m/s, cruise_throttle should be in the range -1 to +1 + float calc_speed_max(float cruise_speed, float cruise_throttle) const; // calculate pilot input to nudge speed up or down // target_speed should be in meters/sec