From ee317299fc931384a8b81e5c90cada28b0b85ca0 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 5 Jan 2022 15:14:25 +0900 Subject: [PATCH] Rover: sailboats enable wpnav's overspeed support --- Rover/sailboat.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Rover/sailboat.cpp b/Rover/sailboat.cpp index 7a8d137212..c547a9cb1f 100644 --- a/Rover/sailboat.cpp +++ b/Rover/sailboat.cpp @@ -141,6 +141,10 @@ void Sailboat::init() // sailboat defaults if (sail_enabled()) { rover.g2.crash_angle.set_default(0); + + // sailboats without motors may travel faster than WP_SPEED so allow waypoint navigation to + // speedup to catch the vehicle instead of asking the vehicle to slow down + rover.g2.wp_nav.enable_overspeed(motor_state != UseMotor::USE_MOTOR_ALWAYS); } if (tack_enabled()) {