Skip to content
Permalink
Browse files

Rover: mode: trigger tack on active fence limits

  • Loading branch information...
IamPete1 committed Aug 22, 2019
1 parent 1b94af6 commit 9c55c249dd9e18470d544ca5ab93d98130d553b2
Showing with 4 additions and 0 deletions.
  1. +4 −0 APMrover2/mode.cpp
@@ -269,6 +269,10 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled)
// apply object avoidance to desired speed using half vehicle's maximum deceleration
if (avoidance_enabled) {
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.yaw, target_speed, rover.G_Dt);
if (g2.sailboat.enabled() && g2.avoid.limits_active()) {
// we are a sailboat trying to avoid fence, try a tack
rover.control_mode->handle_tack_request();
}
}

// call throttle controller and convert output to -100 to +100 range

0 comments on commit 9c55c24

Please sign in to comment.
You can’t perform that action at this time.