mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter Nav: add accessor for waypoint speed
This commit is contained in:
parent
8b87849acd
commit
7a2afb7443
@ -135,6 +135,9 @@ public:
|
||||
/// set_horizontal_velocity - allows main code to pass target horizontal velocity for wp navigation
|
||||
void set_horizontal_velocity(float velocity_cms) { _wp_speed_cms = velocity_cms; };
|
||||
|
||||
/// get_horizontal_velocity - allows main code to retrieve target horizontal velocity for wp navigation
|
||||
float get_horizontal_velocity() { return _wp_speed_cms; };
|
||||
|
||||
/// get_climb_velocity - returns target climb speed in cm/s during missions
|
||||
float get_climb_velocity() const { return _wp_speed_up_cms; };
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user