From 5c04af6d2015a5e7ef80d16dbf60dee12fc6d868 Mon Sep 17 00:00:00 2001
From: Robert Lefebvre <robert.lefebvre@gmail.com>
Date: Thu, 3 Jul 2014 14:08:32 -0400
Subject: [PATCH] AC_AttitudeControl_Heli: Create Flybar Passthrough flag which
 will be used for control pass-through.

---
 libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h | 9 +++++----
 1 file changed, 5 insertions(+), 4 deletions(-)

diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h
index 4fe6aa4a2..445fb4fbf 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;
 
     //
-- 
GitLab