diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index c4cb620f63..fe0c80842d 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -370,7 +370,7 @@ void AC_WPNav::update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler) if (dt >= _pos_control.get_dt_xy()) { // send adjusted feed forward velocity back to position controller - _pos_control.set_desired_velocity_xy(0,0); + _pos_control.set_desired_velocity_xy(0.0f, 0.0f); _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_LIMITED_AND_VEL_FF, ekfNavVelGainScaler, false); } }