From 510c9920a61324dd3c407656ea53ab210d683c88 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 30 Apr 2014 10:48:50 +0900 Subject: [PATCH] AC_WPNav: rename get_horizontal_velocity to get_speed_xy This new method name is consistent with the equivalent in the AC_PosControl class --- libraries/AC_WPNav/AC_WPNav.cpp | 6 +++--- libraries/AC_WPNav/AC_WPNav.h | 16 ++++++++-------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index e47ad79ea7..252e13c4d4 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 f2e71befae..caeaed82c1 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; }