Browse Source

AC_WPNav: params always use set method

apm_2208
Iampete1 3 years ago committed by Peter Hall
parent
commit
ac1b8ab7be
  1. 2
      libraries/AC_WPNav/AC_Circle.cpp
  2. 4
      libraries/AC_WPNav/AC_Loiter.cpp

2
libraries/AC_WPNav/AC_Circle.cpp

@ -135,7 +135,7 @@ void AC_Circle::set_center(const Location& center) @@ -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);
}
}

4
libraries/AC_WPNav/AC_Loiter.cpp

@ -195,8 +195,8 @@ void AC_Loiter::update(bool avoidance_on) @@ -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

Loading…
Cancel
Save