mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Rover: fix initial target when setting Guided
This commit is contained in:
parent
8b9b1fdb66
commit
3ef910ff11
@ -7,9 +7,8 @@ bool ModeGuided::_enter()
|
|||||||
set_desired_speed_to_default();
|
set_desired_speed_to_default();
|
||||||
|
|
||||||
// set desired location to reasonable stopping point
|
// set desired location to reasonable stopping point
|
||||||
Location stopping_point;
|
|
||||||
calc_stopping_location(_destination);
|
calc_stopping_location(_destination);
|
||||||
set_desired_location(stopping_point);
|
set_desired_location(_destination);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user