From 84d3069a77e4c97ac9750ea5a63fdf6e963929d6 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 24 Apr 2015 14:13:29 +0900 Subject: [PATCH] AttControl_Heli: fix compile warning re member init order --- libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index 57f12596f2..987c765b72 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -77,6 +77,9 @@ private: // calculate total body frame throttle required to produce the given earth frame throttle float get_boosted_throttle(float throttle_in); + // pass through for roll and pitch + int16_t _passthrough_roll; + int16_t _passthrough_pitch; // LPF filters to act on Rate Feedforward terms to linearize output. // Due to complicated aerodynamic effects, feedforwards acting too fast can lead @@ -85,9 +88,6 @@ private: LowPassFilterFloat roll_feedforward_filter; LowPassFilterFloat yaw_feedforward_filter; - // pass through for roll and pitch - int16_t _passthrough_roll; - int16_t _passthrough_pitch; }; #endif //AC_ATTITUDECONTROL_HELI_H