mirror of https://github.com/ArduPilot/ardupilot
Rover: add const and comments to calc_speed_max
This commit is contained in:
parent
7dd69f8796
commit
ad7b1061ef
|
@ -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;
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue