Skip to content

Commit

Permalink
AC_AttitudeControl: Write_Rate() should be thread-safe
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Sep 10, 2024
1 parent 8692237 commit 9a54019
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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{
Expand Down

0 comments on commit 9a54019

Please sign in to comment.