mirror of https://github.com/ArduPilot/ardupilot
Rover: correct clamping of RTL_SPEED parameter
MAX wasn't treating these things as floats
This commit is contained in:
parent
e3744e8069
commit
cc243ef53c
|
@ -8,7 +8,7 @@ bool ModeRTL::_enter()
|
|||
}
|
||||
|
||||
// initialise waypoint navigation library
|
||||
g2.wp_nav.init(MAX(0, g2.rtl_speed));
|
||||
g2.wp_nav.init(MAX(0.0f, g2.rtl_speed));
|
||||
|
||||
// set target to the closest rally point or home
|
||||
#if HAL_RALLY_ENABLED
|
||||
|
|
Loading…
Reference in New Issue