mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_WPNav: rename get_speed_xy to get_default_speed_xy
This hopefully clarifies that the default speed is returned and not the current speed
This commit is contained in:
parent
e93dee89b7
commit
b0811c86e7
@ -75,14 +75,14 @@ public:
|
|||||||
/// should be called once before the waypoint controller is used but does not need to be called before subsequent updates to destination
|
/// should be called once before the waypoint controller is used but does not need to be called before subsequent updates to destination
|
||||||
void wp_and_spline_init();
|
void wp_and_spline_init();
|
||||||
|
|
||||||
/// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation
|
/// set current target horizontal speed during wp navigation
|
||||||
void set_speed_xy(float speed_cms);
|
void set_speed_xy(float speed_cms);
|
||||||
|
|
||||||
/// set_speed_z - allows main code to pass target vertical velocity for wp navigation
|
/// set_speed_z - allows main code to pass target vertical velocity for wp navigation
|
||||||
void set_speed_z(float speed_down_cms, float speed_up_cms);
|
void set_speed_z(float speed_down_cms, float speed_up_cms);
|
||||||
|
|
||||||
/// get_speed_xy - allows main code to retrieve target horizontal velocity for wp navigation
|
/// get default target horizontal velocity during wp navigation
|
||||||
float get_speed_xy() const { return _wp_speed_cms; }
|
float get_default_speed_xy() const { return _wp_speed_cms; }
|
||||||
|
|
||||||
/// get_speed_up - returns target climb speed in cm/s during missions
|
/// get_speed_up - returns target climb speed in cm/s during missions
|
||||||
float get_speed_up() const { return _wp_speed_up_cms; }
|
float get_speed_up() const { return _wp_speed_up_cms; }
|
||||||
|
Loading…
Reference in New Issue
Block a user