diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index 4fe6aa4a28f115a6d1daeeae50fa74fe78484363..445fb4fbfcb0d305fd3e9c6b2fde5e3893d8e736 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -47,10 +47,11 @@ private: // To-Do: move these limits flags into the heli motors class struct AttControlHeliFlags { - uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move - uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move - uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move - uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage + uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move + uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move + uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move + uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage + uint8_t flybar_passthrough : 1; // 1 if we should pass through pilots input directly to swash-plate } _flags_heli; //