AC_AttitudeControl: update comment to reflect the current logic in is_active_xy()

This commit is contained in:
Tatsuya Yamaguchi 2024-08-22 17:09:04 +09:00 committed by Peter Barker
parent ecd9694e47
commit 62e3c6a6a9
1 changed files with 2 additions and 2 deletions

View File

@ -611,7 +611,7 @@ void AC_PosControl::stop_vel_xy_stabilisation()
_pid_vel_xy.reset_I();
}
// is_active_xy - returns true if the xy position controller has bee n run in the previous 5 loop times
// is_active_xy - returns true if the xy position controller has been run in the previous loop
bool AC_PosControl::is_active_xy() const
{
const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_xy_ticks;
@ -942,7 +942,7 @@ void AC_PosControl::update_pos_offset_z(float pos_offset_z)
_jerk_max_z_cmsss, _dt, false);
}
// is_active_z - returns true if the z position controller has been run in the previous 5 loop times
// is_active_z - returns true if the z position controller has been run in the previous loop
bool AC_PosControl::is_active_z() const
{
const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_z_ticks;