From c1d3384835daec87b012dbb18ddff3a6844c4da9 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 23 Aug 2016 20:21:28 +0900 Subject: [PATCH] Rover: rename set_next_WP to set_auto_WP to clarify usage --- APMrover2/Rover.h | 2 +- APMrover2/commands.cpp | 6 +++--- APMrover2/commands_logic.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 45a338146a..11f8113437 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -469,7 +469,7 @@ private: void calc_lateral_acceleration(); void calc_nav_steer(); void set_servos(void); - void set_next_WP(const struct Location& loc); + void set_auto_WP(const struct Location& loc); void set_guided_WP(const struct Location& loc); void init_home(); void restart_nav(); diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index 2f1dfaacb4..20b4f2581b 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -5,14 +5,14 @@ void set_guided_WP(void) void init_home() void restart_nav() -************************************************************ +************************************************************ */ /* - * set_next_WP - sets the target location the vehicle should fly to + * set_auto_WP - sets the target location the vehicle should drive to in Auto mode */ -void Rover::set_next_WP(const struct Location& loc) +void Rover::set_auto_WP(const struct Location& loc) { // copy the current WP into the OldWP slot // --------------------------------------- diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index b600f25d8f..41db844d47 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -236,7 +236,7 @@ void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd) Location cmdloc = cmd.content.location; location_sanitize(current_loc, cmdloc); - set_next_WP(cmdloc); + set_auto_WP(cmdloc); } void Rover::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)