mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: sailboats enable wpnav's overspeed support
This commit is contained in:
parent
653afbeb15
commit
ee317299fc
@ -141,6 +141,10 @@ void Sailboat::init()
|
|||||||
// sailboat defaults
|
// sailboat defaults
|
||||||
if (sail_enabled()) {
|
if (sail_enabled()) {
|
||||||
rover.g2.crash_angle.set_default(0);
|
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()) {
|
if (tack_enabled()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user