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 17, 2024
1 parent 516426f commit dc0547c
Showing 1 changed file with 1 addition and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ void AC_AttitudeControl::Write_ANG() const
// 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 dc0547c

Please sign in to comment.