AC_WPNav: rename get_horizontal_velocity to get_speed_xy

This new method name is consistent with the equivalent in the
AC_PosControl class
This commit is contained in:
Randy Mackay 2014-04-30 10:48:50 +09:00
parent eb1fb63e57
commit 510c9920a6
2 changed files with 11 additions and 11 deletions

View File

@ -264,12 +264,12 @@ void AC_WPNav::update_loiter()
/// waypoint navigation /// waypoint navigation
/// ///
/// set_horizontal_velocity - allows main code to pass target horizontal velocity for wp navigation /// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation
void AC_WPNav::set_horizontal_velocity(float velocity_cms) void AC_WPNav::set_speed_xy(float speed_cms)
{ {
// range check new target speed and update position controller // range check new target speed and update position controller
if (_wp_speed_cms >= WPNAV_WP_SPEED_MIN) { 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); _pos_control.set_speed_xy(_wp_speed_cms);
// flag that wp leash must be recalculated // flag that wp leash must be recalculated
_flags.recalc_wp_leash = true; _flags.recalc_wp_leash = true;

View File

@ -88,17 +88,17 @@ public:
/// waypoint controller /// waypoint controller
/// ///
/// set_horizontal_velocity - allows main code to pass target horizontal velocity for wp navigation /// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation
void set_horizontal_velocity(float velocity_cms); void set_speed_xy(float speed_cms);
/// get_horizontal_velocity - allows main code to retrieve target horizontal velocity for wp navigation /// get_speed_xy - allows main code to retrieve target horizontal velocity for wp navigation
float get_horizontal_velocity() const { return _wp_speed_cms; } float get_speed_xy() const { return _wp_speed_cms; }
/// get_climb_velocity - returns target climb speed in cm/s during missions /// get_speed_up - returns target climb speed in cm/s during missions
float get_climb_velocity() const { return _wp_speed_up_cms; } 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 /// get_speed_down - returns target descent speed in cm/s during missions. Note: always positive
float get_descent_velocity() const { return _wp_speed_down_cms; } float get_speed_down() const { return _wp_speed_down_cms; }
/// get_wp_radius - access for waypoint radius in cm /// get_wp_radius - access for waypoint radius in cm
float get_wp_radius() const { return _wp_radius_cm; } float get_wp_radius() const { return _wp_radius_cm; }