mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Rover: pass waypoint radius to L1 as min dist along track
This commit is contained in:
parent
4f0b26bd48
commit
e8070a5cb3
@ -314,7 +314,7 @@ void Mode::calc_steering_to_waypoint(const struct Location &origin, const struct
|
|||||||
// negative error = left turn
|
// negative error = left turn
|
||||||
// positive error = right turn
|
// positive error = right turn
|
||||||
rover.nav_controller->set_reverse(reversed);
|
rover.nav_controller->set_reverse(reversed);
|
||||||
rover.nav_controller->update_waypoint(origin, destination);
|
rover.nav_controller->update_waypoint(origin, destination, g.waypoint_radius);
|
||||||
float desired_lat_accel = rover.nav_controller->lateral_acceleration();
|
float desired_lat_accel = rover.nav_controller->lateral_acceleration();
|
||||||
float desired_heading = rover.nav_controller->target_bearing_cd();
|
float desired_heading = rover.nav_controller->target_bearing_cd();
|
||||||
if (reversed) {
|
if (reversed) {
|
||||||
|
Loading…
Reference in New Issue
Block a user