AC_AttitudeControl: Write_Rate() should be thread-safe

This commit is contained in:
Andy Piper 2024-09-10 18:00:08 +01:00 committed by Peter Barker
parent 829422ecfb
commit 70067ea7ae
1 changed files with 1 additions and 1 deletions

View File

@ -30,7 +30,7 @@ void AC_AttitudeControl::Write_ANG() const
// Write a rate packet // Write a rate packet
void AC_AttitudeControl::Write_Rate(const AC_PosControl &pos_control) const void AC_AttitudeControl::Write_Rate(const AC_PosControl &pos_control) const
{ {
const Vector3f &rate_targets = rate_bf_targets(); const Vector3f rate_targets = rate_bf_targets();
const Vector3f &accel_target = pos_control.get_accel_target_cmss(); const Vector3f &accel_target = pos_control.get_accel_target_cmss();
const Vector3f &gyro_rate = _rate_gyro; const Vector3f &gyro_rate = _rate_gyro;
const struct log_Rate pkt_rate{ const struct log_Rate pkt_rate{