From 9a540196c9fa7b00b7d8b34c5adeb9437e046dd8 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 10 Sep 2024 18:00:08 +0100 Subject: [PATCH] AC_AttitudeControl: Write_Rate() should be thread-safe --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 62fa5ebd5a9784..25f218d13ffa01 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -1276,7 +1276,7 @@ void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, fl // Write a rate packet 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 &gyro_rate = _rate_gyro; const struct log_Rate pkt_rate{