diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 3da13dcef1..59877b4e61 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -135,7 +135,7 @@ void AC_Circle::set_center(const Location& center) void AC_Circle::set_rate(float deg_per_sec) { if (!is_equal(deg_per_sec, _rate.get())) { - _rate = deg_per_sec; + _rate.set(deg_per_sec); } } diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index 0e66fdfe44..f8e0565ed7 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -195,8 +195,8 @@ void AC_Loiter::update(bool avoidance_on) // sanity check parameters void AC_Loiter::sanity_check_params() { - _speed_cms = MAX(_speed_cms, LOITER_SPEED_MIN); - _accel_cmss = MIN(_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max_cd() * 0.01f))); + _speed_cms.set(MAX(_speed_cms, LOITER_SPEED_MIN)); + _accel_cmss.set(MIN(_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max_cd() * 0.01f)))); } /// calc_desired_velocity - updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance