diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index b146ddc325..6d135b9135 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -339,7 +339,7 @@ bool AP_Landing_Deepstall::override_servos(void) // use the current airspeed to dictate the travel limits float airspeed; - if (!landing.ahrs.airspeed_estimate(&airspeed)) { + if (!landing.ahrs.airspeed_estimate(airspeed)) { airspeed = 0; // safely forces control to the deepstall steering since we don't have an estimate }