diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index e47ad79ea77dd1d895e697eab90b0507f716f7b1..252e13c4d44d148cf390551edfd22d9563f231c0 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -264,12 +264,12 @@ void AC_WPNav::update_loiter() /// waypoint navigation /// -/// set_horizontal_velocity - allows main code to pass target horizontal velocity for wp navigation -void AC_WPNav::set_horizontal_velocity(float velocity_cms) +/// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation +void AC_WPNav::set_speed_xy(float speed_cms) { // range check new target speed and update position controller if (_wp_speed_cms >= WPNAV_WP_SPEED_MIN) { - _wp_speed_cms = velocity_cms; + _wp_speed_cms = speed_cms; _pos_control.set_speed_xy(_wp_speed_cms); // flag that wp leash must be recalculated _flags.recalc_wp_leash = true; diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index f2e71befaef828dabcea7bbe695e85a7b38a30fd..caeaed82c17776be3c35324ef19a35adbb1f18c2 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -88,17 +88,17 @@ public: /// waypoint controller /// - /// set_horizontal_velocity - allows main code to pass target horizontal velocity for wp navigation - void set_horizontal_velocity(float velocity_cms); + /// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation + void set_speed_xy(float speed_cms); - /// get_horizontal_velocity - allows main code to retrieve target horizontal velocity for wp navigation - float get_horizontal_velocity() const { return _wp_speed_cms; } + /// get_speed_xy - allows main code to retrieve target horizontal velocity for wp navigation + float get_speed_xy() const { 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; } + /// get_speed_up - returns target climb speed in cm/s during missions + float get_speed_up() const { return _wp_speed_up_cms; } - /// get_descent_velocity - returns target descent speed in cm/s during missions. Note: always positive - float get_descent_velocity() const { return _wp_speed_down_cms; } + /// get_speed_down - returns target descent speed in cm/s during missions. Note: always positive + float get_speed_down() const { return _wp_speed_down_cms; } /// get_wp_radius - access for waypoint radius in cm float get_wp_radius() const { return _wp_radius_cm; }