Rover: rename set_next_WP to set_auto_WP to clarify usage

This commit is contained in:
Randy Mackay 2016-08-23 20:21:28 +09:00 committed by Grant Morphett
parent d6b55b2d09
commit c1d3384835
3 changed files with 5 additions and 5 deletions

View File

@ -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();

View File

@ -10,9 +10,9 @@
/*
* 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
// ---------------------------------------

View File

@ -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)