AC_AttitudeControl_Heli: Create Flybar Passthrough flag which will be used for control pass-through.

This commit is contained in:
Robert Lefebvre 2014-07-03 14:08:32 -04:00 committed by Randy Mackay
parent 0ab3e40e92
commit 5c04af6d20

View File

@ -47,10 +47,11 @@ private:
// To-Do: move these limits flags into the heli motors class // To-Do: move these limits flags into the heli motors class
struct AttControlHeliFlags { struct AttControlHeliFlags {
uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move 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_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 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 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; } _flags_heli;
// //