mirror of https://github.com/ArduPilot/ardupilot
Rover: rename set_next_WP to set_auto_WP to clarify usage
This commit is contained in:
parent
d6b55b2d09
commit
c1d3384835
|
@ -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();
|
||||
|
|
|
@ -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
|
||||
// ---------------------------------------
|
||||
|
|
|
@ -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)
|
||||
|
|
Loading…
Reference in New Issue