mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Rover: navigate-to-waypoint leaves simple avoidance to position controller
also navigate-to-waypoint may trigger tacking
This commit is contained in:
parent
aea6b48d70
commit
f7a33a8900
@ -431,8 +431,15 @@ void Mode::navigate_to_waypoint()
|
|||||||
g2.wp_nav.update(rover.G_Dt);
|
g2.wp_nav.update(rover.G_Dt);
|
||||||
_distance_to_destination = g2.wp_nav.get_distance_to_destination();
|
_distance_to_destination = g2.wp_nav.get_distance_to_destination();
|
||||||
|
|
||||||
|
// sailboats trigger tack if simple avoidance becomes active
|
||||||
|
if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {
|
||||||
|
// we are a sailboat trying to avoid fence, try a tack
|
||||||
|
rover.control_mode->handle_tack_request();
|
||||||
|
}
|
||||||
|
|
||||||
// pass desired speed to throttle controller
|
// pass desired speed to throttle controller
|
||||||
calc_throttle(g2.wp_nav.get_speed(), true);
|
// do not do simple avoidance because this is already handled in the position controller
|
||||||
|
calc_throttle(g2.wp_nav.get_speed(), false);
|
||||||
|
|
||||||
float desired_heading_cd = g2.wp_nav.oa_wp_bearing_cd();
|
float desired_heading_cd = g2.wp_nav.oa_wp_bearing_cd();
|
||||||
if (g2.sailboat.use_indirect_route(desired_heading_cd)) {
|
if (g2.sailboat.use_indirect_route(desired_heading_cd)) {
|
||||||
|
Loading…
Reference in New Issue
Block a user