mirror of https://github.com/ArduPilot/ardupilot
Rover: remove unused distance_past_wp
This commit is contained in:
parent
a00c7e0acb
commit
bff74115bc
|
@ -368,7 +368,6 @@ private:
|
||||||
// Loiter control
|
// Loiter control
|
||||||
uint16_t loiter_duration; // How long we should loiter at the nav_waypoint (time in seconds)
|
uint16_t loiter_duration; // How long we should loiter at the nav_waypoint (time in seconds)
|
||||||
uint32_t loiter_start_time; // How long have we been loitering - The start time in millis
|
uint32_t loiter_start_time; // How long have we been loitering - The start time in millis
|
||||||
float distance_past_wp; // record the distance we have gone past the wp
|
|
||||||
bool previously_reached_wp; // set to true if we have EVER reached the waypoint
|
bool previously_reached_wp; // set to true if we have EVER reached the waypoint
|
||||||
|
|
||||||
// time that rudder/steering arming has been running
|
// time that rudder/steering arming has been running
|
||||||
|
|
|
@ -228,9 +228,6 @@ void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool stay_active_a
|
||||||
// this is the delay, stored in seconds
|
// this is the delay, stored in seconds
|
||||||
loiter_duration = cmd.p1;
|
loiter_duration = cmd.p1;
|
||||||
|
|
||||||
// this is the distance we travel past the waypoint - not there yet so 0 initially
|
|
||||||
distance_past_wp = 0;
|
|
||||||
|
|
||||||
Location cmdloc = cmd.content.location;
|
Location cmdloc = cmd.content.location;
|
||||||
location_sanitize(current_loc, cmdloc);
|
location_sanitize(current_loc, cmdloc);
|
||||||
mode_auto.set_desired_location(cmdloc, stay_active_at_dest);
|
mode_auto.set_desired_location(cmdloc, stay_active_at_dest);
|
||||||
|
|
Loading…
Reference in New Issue