From c6b84f522696fe63f50b9dce398fee8ff7fe4c2a Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 16:40:51 -0500 Subject: [PATCH] Attitude estimator hot fix. --- src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index f56e3ad243..6c78c583b1 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -544,7 +544,7 @@ void AttitudeEstimatorQ::task_main() ctrl_state.pitch_rate = _lp_pitch_rate.apply(_rates(1)); - ctrl_state.roll_rate = _rates(2); + ctrl_state.yaw_rate = _rates(2); /* Publish to control state topic */ if (_ctrl_state_pub == nullptr) {