Rover: guided mode slows to stopping point on init
This commit is contained in:
parent
77598f72d1
commit
5dc4b8e66d
@ -6,8 +6,10 @@ bool ModeGuided::_enter()
|
||||
// initialise waypoint speed
|
||||
set_desired_speed_to_default();
|
||||
|
||||
// when entering guided mode we set the target as the current location.
|
||||
set_desired_location(rover.current_loc);
|
||||
// set desired location to reasonable stopping point
|
||||
Location stopping_point;
|
||||
calc_stopping_location(_destination);
|
||||
set_desired_location(stopping_point);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user