{
  "#JSBSim": {
    "Model": "mAEWing2",
    "ImuPort": 59011,
    "GpsPort": 59012,
    "5hole1Port": 59014,
    "CmdHost": "192.168.7.1",
    "CmdPort": 59051
  },

  "Sensors": [
      { "Type": "Time", "Output": "Fmu/Time_us"},
      { "Type": "InputVoltage", "Output": "Fmu/Voltage/Input_V"},
      { "Type": "RegulatedVoltage", "Output": "Fmu/Voltage/Regulated_V"},
      { "Type": "InternalMpu9250", "Output": "Fmu/Mpu9250", "Rotation": [-1,0,0,0,0,1,0,1,0], "SRD": 19, "DLPF-Bandwidth": "20Hz"},
      { "Type": "InternalBme280", "Output": "Fmu/Bme280"},
      { "Type": "Sbus", "Output": "Sbus"},
      { "Type": "uBlox", "Output": "uBlox", "Uart": 4, "Baud": 115200},
      { "Type": "Ams5915", "Output": "5Hole/Static", "Address": 24, "Transducer": "AMS5915-1200-B"},
      { "Type": "Ams5915", "Output": "5Hole/Tip", "Address": 25, "Transducer": "AMS5915-0020-D"},
      { "Type": "Ams5915", "Output": "5Hole/Alpha1", "Address": 32, "Transducer": "AMS5915-0020-D-B"},
      { "Type": "Ams5915", "Output": "5Hole/Alpha2", "Address": 33, "Transducer": "AMS5915-0020-D-B"},
      { "Type": "Ams5915", "Output": "5Hole/Beta1", "Address": 28, "Transducer": "AMS5915-0020-D-B"},
      { "Type": "Ams5915", "Output": "5Hole/Beta2", "Address": 29, "Transducer": "AMS5915-0020-D-B"},

      { "Type": "Node", "Address": 3,
        "Sensors": [
          { "Type": "Analog", "Output": "Power/voltAvionics", "Channel": 0, "Calibration": [7.1200, 0]},
          { "Type": "Analog", "Output": "Power/currAvionics", "Channel": 1, "Calibration": [27.3224, 0]},
          { "Type": "Analog", "Output": "Power/voltPropLeft", "Channel": 2, "Calibration": [15.8053, 0]},
          { "Type": "Analog", "Output": "Power/currPropLeft", "Channel": 3, "Calibration": [65.5364, 0]},
          { "Type": "Analog", "Output": "Power/voltPropRight", "Channel": 5, "Calibration": [15.8053, 0]},
          { "Type": "Analog", "Output": "Power/currPropRight", "Channel": 6, "Calibration": [65.5364, 0]},
          { "Type": "Mpu9250", "Output": "Imu/CenterFwd",
            "UseSpi": 1, "CsPin": 25, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [1,0,0, 0,0,1, 0,-1,0], "SRD": 19},
          { "Type": "Mpu9250", "Output": "Imu/CenterAft",
            "UseSpi": 1, "CsPin": 26, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [1,0,0, 0,0,1, 0,-1,0], "SRD": 19}
        ]
      },

      { "Type": "Node", "Address": 4,
        "Sensors": [
          { "Type": "Analog", "Output": "Surf/posTE1L", "Channel": 0, "Calibration": [1.14680560, -1.81621446]},
          { "Type": "Analog", "Output": "Surf/posTE2L", "Channel": 1, "Calibration": [1.29409403, -2.31206750]},
          { "Type": "Analog", "Output": "Surf/posTE3L", "Channel": 2, "Calibration": [1.02036440, -1.89261982]},
          { "Type": "Analog", "Output": "Surf/posTE4L", "Channel": 3, "Calibration": [1.21640293, -2.18756403]},
          { "Type": "Analog", "Output": "Surf/posTE5L", "Channel": 5, "Calibration": [1.16484893, -1.80075646]},
          { "Type": "Analog", "Output": "Surf/posLEL", "Channel": 6, "Calibration": [-1.20863271, 1.99022805]},
          { "Type": "Mpu9250", "Output": "Imu/LeftMid",
            "UseSpi": 1, "CsPin": 24, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [-0.92718385,0,-0.37460659, 0.37460659,0,-0.92718385, 0,-1,0], "SRD": 19},
          { "Type": "Mpu9250", "Output": "Imu/LeftFwd",
            "UseSpi": 1, "CsPin": 25, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [0,1,0, -1,0,0, 0,0,1], "SRD": 19},
          { "Type": "Mpu9250", "Output": "Imu/LeftAft",
            "UseSpi": 1, "CsPin": 26, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [0,1,0, -1,0,0, 0,0,1], "SRD": 19}
        ]
      },

      { "Type": "Node", "Address": 5,
        "Sensors": [
          { "Type": "Analog", "Output": "Surf/posTE1R", "Channel": 0, "Calibration": [-1.17079614, 1.95978482]},
          { "Type": "Analog", "Output": "Surf/posTE2R", "Channel": 1, "Calibration": [-1.28476186, 2.21270030]},
          { "Type": "Analog", "Output": "Surf/posTE3R", "Channel": 2, "Calibration": [-1.14332543, 1.67660296]},
          { "Type": "Analog", "Output": "Surf/posTE4R", "Channel": 3, "Calibration": [-1.21485676, 1.70072795]},
          { "Type": "Analog", "Output": "Surf/posTE5R", "Channel": 5, "Calibration": [-1.21485676, 1.70072795]},
          { "Type": "Analog", "Output": "Surf/posLER", "Channel": 6, "Calibration": [1.08981167, -1.89890412]},
          { "Type": "Mpu9250", "Output": "Imu/RightMid",
            "UseSpi": 1, "CsPin": 24, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [0.92718385,0,-0.37460659, 0.37460659,0,0.92718385, 0,-1,0], "SRD": 19},
          { "Type": "Mpu9250", "Output": "Imu/RightFwd",
            "UseSpi": 1, "CsPin": 25, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [0,1,0, -1,0,0, 0,0,1], "SRD": 19},
          { "Type": "Mpu9250", "Output": "Imu/RightAft",
            "UseSpi": 1, "CsPin": 26, "MosiPin": 7, "MisoPin": 8, "SckPin": 14,
            "Rotation": [0,1,0, -1,0,0, 0,0,1], "SRD": 19}
        ]
      }
    ],

  "Effectors": [
    { "Type": "Node", "Address": 3,
      "Effectors": [
        { "Type": "Motor", "Input": "/Control/cmdMotor_nd", "Channel": 0, "Calibration": [800, 1100], "Safed-Command": 0},
        { "Type": "Motor", "Input": "/Control/cmdMotor_nd", "Channel": 1, "Calibration": [800, 1100], "Safed-Command": 0},
        { "Type": "Pwm", "Input": "/Control/cmdGear_nd", "Channel": 3, "Calibration": [500, 1500]},
        { "Type": "Pwm", "Input": "/Control/cmdSkid_nd", "Channel": 7, "Calibration": [250, 1750]}
      ]
    },

    { "Type": "Node", "Address": 4,
      "Effectors": [
        { "Type": "Sbus", "Input": "/Control/cmdTE1L_rad", "Channel": 0, "Calibration": [ 0.00000000, 103.36532115, -883.78440854, 944.91554365]},
        { "Type": "Sbus", "Input": "/Control/cmdTE2L_rad", "Channel": 1, "Calibration": [ 0.00000000, 172.50356555, -841.72227709, 1025.47125771]},
        { "Type": "Sbus", "Input": "/Control/cmdTE3L_rad", "Channel": 2, "Calibration": [ 0.00000000, 77.00144288, -858.81792120, 993.16934942]},
        { "Type": "Sbus", "Input": "/Control/cmdTE4L_rad", "Channel": 3, "Calibration": [ 0.00000000, 73.38412980, -870.95304252, 1040.29434188]},
        { "Type": "Sbus", "Input": "/Control/cmdTE5L_rad", "Channel": 4, "Calibration": [ 0.00000000, 53.09678075, -867.86055024, 1043.97333521]},
        { "Type": "Sbus", "Input": "/Control/cmdLEL_rad", "Channel": 5, "Calibration": [ 0.00000000, 0.00000000, 894.85287343, 997.78449303]}
      ]
    },

    { "Type": "Node", "Address": 5,
      "Effectors": [
        { "Type": "Sbus", "Input": "/Control/cmdTE1R_rad", "Channel": 0, "Calibration": [ 0.00000000, 55.20246265, 921.72064822, 998.27858984]},
        { "Type": "Sbus", "Input": "/Control/cmdTE2R_rad", "Channel": 1, "Calibration": [ 0.00000000, 61.59912377, 933.48595242, 1028.50500276]},
        { "Type": "Sbus", "Input": "/Control/cmdTE3R_rad", "Channel": 2, "Calibration": [ 0.00000000, -74.14832495, 898.28218523, 1024.46677726]},
        { "Type": "Sbus", "Input": "/Control/cmdTE4R_rad", "Channel": 3, "Calibration": [ 0.00000000, -12.46335758, 842.36276278, 1020.78343852]},
        { "Type": "Sbus", "Input": "/Control/cmdTE5R_rad", "Channel": 4, "Calibration": [ 0.00000000, -13.54748650, 842.19014163, 1020.88938916]},
        { "Type": "Sbus", "Input": "/Control/cmdLER_rad", "Channel": 5, "Calibration": [ 0.00000000, 74.32679318, -878.38823564, 1022.08606270]}
      ]
    }
  ],

  "Sensor-Processing": {
    "Baseline": [
      {
        "Type": "FiveHole1", "Output": "5Hole",
        "OutputIas": "vIAS_ms", "OutputAltitude": "hBaro_m", "OutputAlpha": "alpha_rad", "OutputBeta": "beta_rad",
        "Static-Pressure": "/Sensors/5Hole/Static/Pressure_Pa", "Tip-Pressure": "/Sensors/5Hole/Tip/Pressure_Pa", "Alpha1-Pressure": "/Sensors/5Hole/Alpha1/Pressure_Pa", "Alpha2-Pressure": "/Sensors/5Hole/Alpha2/Pressure_Pa", "Beta1-Pressure": "/Sensors/5Hole/Beta1/Pressure_Pa", "Beta2-Pressure": "/Sensors/5Hole/Beta2/Pressure_Pa",
        "Alpha-Calibration": 4.8071159, "Beta-Calibration": 4.8071159, "Initialization-Time": 10
      },
      { "Type": "EKF15StateINS", "Output": "INS",
        "Time": "/Sensors/Fmu/Time_us", "GPS": "/Sensors/uBlox", "IMU": "/Sensors/Fmu/Mpu9250"
      },
      { "Type": "MinCellVolt", "Output": "MinCellVolt_V",
        "Inputs": ["/Sensors/Fmu/Voltage/Input_V", "/Sensors/Power/voltPropLeft/CalibratedValue", "/Sensors/Power/voltPropRight/CalibratedValue"],
        "NumCells": [3, 12, 12]
      }
    ]
  },

  "Telemetry": {
    "Uart": "/dev/ttyO2",
    "Baud": 115200,
    "Time": "/Sensors/Fmu/Time_us",
    "Static-Pressure": "/Sensors/Fmu/Bme280",
    "Airspeed": "/Sensor-Processing/vIAS_ms",
    "Altitude": "/Sensor-Processing/hBaro_m",
    "Filter": "/Sensor-Processing",
    "Gps": "/Sensors/uBlox",
    "Imu": "/Sensors/Fmu/Mpu9250",
    "Sbus": "/Sensors/Sbus",
    "Power": "/Sensor-Processing"
  },

  "Control": {
    "Fmu": "PilotDirect",
    "Soc": [
      "PilotAttitudeLaunch",
      "PilotAttitudeMan",
      "PilotAttitudeLand",
      "PilotAttitude26",
      "PilotAttitude29"],

    "PilotDirect": [
      { "Level": "Pilot-Rates",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/7", "Output": "cmdMotor_nd", "Gain": 1.0, "Limits": {"Upper": 1.0, "Lower": 0.0}},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refRoll_rps", "Gain": 0.523599},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refPitch_rps", "Gain": 0.349066},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/11", "Output": "cmdGear_nd", "Gain": -1.0, "Limits": {"Upper": -1.0, "Lower": -1.0}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "Gain", "Input": "/Control/refFlap_nd", "Output": "cmdTE1L_rad", "Gain": 0.436332, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refFlap_nd", "Output": "cmdTE1R_rad", "Gain": 0.436332, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refRoll_rps", "Output": "cmdTE2L_rad", "Gain": 0.46631, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refRoll_rps", "Output": "cmdTE2R_rad", "Gain": -0.46631, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refRoll_rps", "Output": "cmdTE3L_rad", "Gain": 0.61633, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refRoll_rps", "Output": "cmdTE3R_rad", "Gain": -0.61633, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refPitch_rps", "Output": "cmdTE4L_rad", "Gain": -0.44899, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refPitch_rps", "Output": "cmdTE4R_rad", "Gain": -0.44899, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refPitch_rps", "Output": "cmdTE5L_rad", "Gain": -0.5371, "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/refPitch_rps", "Output": "cmdTE5R_rad", "Gain": -0.5371, "Limits": {"Upper": 0.436332, "Lower": -0.436332}}
        ]
      }
    ],

    "PilotRate": [
      { "Level": "Pilot-Rates",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/7", "Output": "cmdMotor_nd", "Gain": 1.0, "Limits": {"Upper": 1.0, "Lower": 0.0}},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refRoll_rps", "Gain": 0.523599},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refPitch_pilot_rps", "Gain": 0.349066},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": -1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": 1},

          { "Type": "Constant", "Output": "refPitch_bias_rps", "Constant": 0.25}
        ]
      },

      { "Level": "Pilot-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/refPitch_pilot_rps", "/Control/refPitch_bias_rps"], "Output": "refPitch_rps"}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refRoll_rps", "Output": "cmdRoll_rps",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refPitch_rps", "Output": "cmdPitch_rps",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0]
              ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitudeLaunch": [
      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/7", "Output": "cmdThrust", "Gain": 1, "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_pilot_rad", "Gain": 1.0472},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": -1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": 1},

          { "Type": "Constant", "Output": "refTheta_bias_rad", "Constant": 0.349066}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},

          { "Type": "Sum", "Inputs": ["/Control/refTheta_pilot_rad", "/Control/refTheta_bias_rad"], "Output": "refTheta_rad"}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.40, "Integral": 0.0},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.020},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.0},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.007202], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitudeMan": [
      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/7", "Output": "cmdThrust", "Gain": 1, "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": 1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": -1}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.40, "Integral": 0.05},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.020},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.143},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.007202], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitudeLand": [
      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/7", "Output": "cmdThrust", "Gain": 1, "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_rad", "Gain": 1.0472},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": -1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": -1}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.40, "Integral": 0.05},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.020},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.143},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.007202], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitude20": [
      { "Level": "Guidance-Ref",
        "Components": [
          { "Type": "Constant", "Output": "refV_ms", "Constant": 20},
          { "Type": "Latch", "Input": "/Sensor-Processing/hBaro_m", "Output": "refH_m"}
        ]
      },

      { "Level": "Guidance",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refV_ms", "Feedback": "/Sensor-Processing/vIAS_ms", "Output": "cmdThrust",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.177, "Integral": 0.0355},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "PID2", "Reference": "/Control/refH_m", "Feedback": "/Sensor-Processing/hBaro_m", "Output": "refTheta_guid_rad",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.00698, "Integral": 0.00000, "Derivative": 0.00698},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 0.0873, "Lower": -0.0873}}
        ]
      },

      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_pilot_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": 1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": -1}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Sum", "Inputs": ["/Control/refTheta_guid_rad", "/Control/refTheta_pilot_rad"], "Output": "refTheta_rad",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.20, "Integral": 0.01},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.0008},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.143},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.007202], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitude23": [
      { "Level": "Guidance-Ref",
        "Components": [
          { "Type": "Constant", "Output": "refV_ms", "Constant": 23},
          { "Type": "Latch", "Input": "/Sensor-Processing/hBaro_m", "Output": "refH_m"}
        ]
      },

      { "Level": "Guidance",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refV_ms", "Feedback": "/Sensor-Processing/vIAS_ms", "Output": "cmdThrust",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.177, "Integral": 0.0355},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "PID2", "Reference": "/Control/refH_m", "Feedback": "/Sensor-Processing/hBaro_m", "Output": "refTheta_guid_rad",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.00698, "Integral": 0.00000, "Derivative": 0.00698},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 0.0873, "Lower": -0.0873}}
        ]
      },

      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_pilot_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": 1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": -1}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Sum", "Inputs": ["/Control/refTheta_guid_rad", "/Control/refTheta_pilot_rad"], "Output": "refTheta_rad",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.20, "Integral": 0.01},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.0008},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.143},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.007202], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitude26": [
      { "Level": "Guidance-Ref",
        "Components": [
          { "Type": "Constant", "Output": "refV_ms", "Constant": 26},
          { "Type": "Latch", "Input": "/Sensor-Processing/hBaro_m", "Output": "refH_m"}
        ]
      },

      { "Level": "Guidance",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refV_ms", "Feedback": "/Sensor-Processing/vIAS_ms", "Output": "cmdThrust",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.177, "Integral": 0.0355},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "PID2", "Reference": "/Control/refH_m", "Feedback": "/Sensor-Processing/hBaro_m", "Output": "refTheta_guid_rad",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.00698, "Integral": 0.00000, "Derivative": 0.00698},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 0.0873, "Lower": -0.0873}}
        ]
      },

      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_pilot_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": 1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": -1}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Sum", "Inputs": ["/Control/refTheta_guid_rad", "/Control/refTheta_pilot_rad"], "Output": "refTheta_rad",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.20, "Integral": 0.01},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.0008},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.143},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.007202], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitude29": [
      { "Level": "Guidance-Ref",
        "Components": [
          { "Type": "Constant", "Output": "refV_ms", "Constant": 29},
          { "Type": "Latch", "Input": "/Sensor-Processing/hBaro_m", "Output": "refH_m"}
        ]
      },

      { "Level": "Guidance",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refV_ms", "Feedback": "/Sensor-Processing/vIAS_ms", "Output": "cmdThrust",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.252, "Integral": 0.0505},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "PID2", "Reference": "/Control/refH_m", "Feedback": "/Sensor-Processing/hBaro_m", "Output": "refTheta_guid_rad",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.00524, "Integral": 0.00000, "Derivative": 0.00262},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 0.0873, "Lower": -0.0873}}
        ]
      },

      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_pilot_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": 1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": -1}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Sum", "Inputs": ["/Control/refTheta_guid_rad", "/Control/refTheta_pilot_rad"], "Output": "refTheta_rad",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.20, "Integral": 0.01},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.0008},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.143},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.003415], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ],

    "PilotAttitude32": [
      { "Level": "Guidance-Ref",
        "Components": [
          { "Type": "Constant", "Output": "refV_ms", "Constant": 32},
          { "Type": "Latch", "Input": "/Sensor-Processing/hBaro_m", "Output": "refH_m"}
        ]
      },

      { "Level": "Guidance",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refV_ms", "Feedback": "/Sensor-Processing/vIAS_ms", "Output": "cmdThrust",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.252, "Integral": 0.0505},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 1, "Lower": 0}},
          { "Type": "PID2", "Reference": "/Control/refH_m", "Feedback": "/Sensor-Processing/hBaro_m", "Output": "refTheta_guid_rad",
            "Sample-Time": 0.02, "Time-Constant": 0.2,
            "Gains": {"Proportional": 0.00524, "Integral": 0.00000, "Derivative": 0.00262},
            "Setpoint-Weights": {"Proportional": 1.0, "Derivative": 0.0},
            "Limits": {"Upper": 0.0873, "Lower": -0.0873}}
        ]
      },

      { "Level": "Pilot-Attitude",
        "Components": [
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/3", "Output": "refPhi_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/4", "Output": "refTheta_pilot_rad", "Gain": 0.7854},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/6", "Output": "refFlap_nd", "Gain": 1.0},
          { "Type": "Gain", "Input": "/Sensors/Sbus/Channels/12", "Output": "refBend_nd", "Gain": 1.0},
          { "Type": "Constant", "Output": "cmdGear_nd", "Constant": 1},
          { "Type": "Constant", "Output": "cmdSkid_nd", "Constant": -1}
        ]
      },

      { "Level": "Pilot-Filt",
        "Components": [
          { "Type": "Filter", "Input": "/Control/refFlap_nd", "Output": "cmdFlap_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Filter", "Input": "/Control/refBend_nd", "Output": "cmdBend_nd",
            "b": [0.131311455359006, 0.0863219057948165], "a": [1.0, -1.06697618218221, 0.284609543336029]},
          { "Type": "Sum", "Inputs": ["/Control/refTheta_guid_rad", "/Control/refTheta_pilot_rad"], "Output": "refTheta_rad",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "SCAS-Attitude",
        "Components": [
          { "Type": "PID2", "Reference": "/Control/refPhi_rad", "Feedback": "/Sensor-Processing/Roll_rad", "Output": "cmdRoll_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.20, "Integral": 0.01},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Gain", "Input": "/Sensor-Processing/GyroX_rads", "Output": "cmdRoll_Damp_rps", "Gain": -0.0008},

          { "Type": "PID2", "Reference": "/Control/refTheta_rad", "Feedback": "/Sensor-Processing/Pitch_rad", "Output": "cmdPitch_PID_rps",
            "Sample-Time": 0.02,
            "Gains": {"Proportional": 0.286, "Integral": 0.143},
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}},
          { "Type": "Filter", "Input": "/Control/cmdThrust", "Output": "cmdPitch_cross_rps",
            "b": [0.003415], "a": [1.0, -0.9231]}
        ]
      },

      { "Level": "SCAS-Sum",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdRoll_PID_rps", "/Control/cmdRoll_Damp_rps"], "Output": "cmdRoll_rps",
          "Limits": {"Upper": 0.7854, "Lower": -0.7854}},

          { "Type": "Sum", "Inputs": ["/Control/cmdPitch_PID_rps", "/Control/cmdPitch_cross_rps"], "Output": "cmdPitch_rps",
            "Limits": {"Upper": 0.7854, "Lower": -0.7854}}
        ]
      },

      { "Level": "Allocator",
        "Components": [
          { "Type": "PseudoInverse",
            "Inputs": ["/Control/cmdRoll_rps", "/Control/cmdPitch_rps", "/Control/cmdBend_nd"],
            "Outputs": ["cmdTE1L_alloc_rad", "cmdTE1R_alloc_rad", "cmdTE2L_alloc_rad", "cmdTE2R_alloc_rad", "cmdTE3L_alloc_rad", "cmdTE3R_alloc_rad", "cmdTE4L_rad", "cmdTE4R_rad", "cmdTE5L_alloc_rad", "cmdTE5R_alloc_rad", "cmdLEL_rad", "cmdLER_rad"],
            "Effectiveness": [
              [0,0,0.12566766209044647,-0.12566766209044647,0.17400791474534627,-0.17400791474534627,0.2107643429473072,-0.2107643429473072,0.21455703129167966,-0.21455703129167966,0,0],
              [0,0,0,0,-0.24059736290652464,-0.24059736290652464,-0.37964759401991566,-0.37964759401991566,-0.45864997674431435,-0.45864997674431435,0,0],
              [0.14738379976087307,0.14738379976087307,0.657798596332605,0.657798596332605,0.2576476343713448,0.2576476343713448,-0.821207164723005,-0.821207164723005,-1.9952776060457902,-1.9952776060457902,-0.19101043150067268,-0.19101043150067268]
            ],
            "Limits": {
              "Lower": [-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.436332,-0.2,-0.2],
              "Upper": [ 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.436332, 0.2, 0.2]
            }
          },
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1L_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE1R_flap_rad", "Gain": 0.34907},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2L_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE2R_flap_rad", "Gain": 0.30183},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3L_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE3R_flap_rad", "Gain": 0.23263},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5L_flap_rad", "Gain": -0.21468},
          { "Type": "Gain", "Input": "/Control/cmdFlap_nd", "Output": "cmdTE5R_flap_rad", "Gain": -0.21468}
        ]
      },

      { "Level": "Effector",
        "Components": [
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1L_alloc_rad", "/Control/cmdTE1L_flap_rad"], "Output": "cmdTE1L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE1R_alloc_rad", "/Control/cmdTE1R_flap_rad"], "Output": "cmdTE1R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2L_alloc_rad", "/Control/cmdTE2L_flap_rad"], "Output": "cmdTE2L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE2R_alloc_rad", "/Control/cmdTE2R_flap_rad"], "Output": "cmdTE2R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3L_alloc_rad", "/Control/cmdTE3L_flap_rad"], "Output": "cmdTE3L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE3R_alloc_rad", "/Control/cmdTE3R_flap_rad"], "Output": "cmdTE3R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5L_alloc_rad", "/Control/cmdTE5L_flap_rad"], "Output": "cmdTE5L_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Sum", "Inputs": ["/Control/cmdTE5R_alloc_rad", "/Control/cmdTE5R_flap_rad"], "Output": "cmdTE5R_rad", "Limits": {"Upper": 0.436332, "Lower": -0.436332}},
          { "Type": "Gain", "Input": "/Control/cmdThrust", "Output": "cmdMotor_nd", "Gain": 1.0}
        ]
      },

      { "Level": "Out",
        "Components": []
      }
    ]

  },

  "Excitation": {
    "Time": "/Sensors/Fmu/Time_us",
    "Groups": [
      { "Name": "RTSM", "Components": [
        { "Level": "Allocator", "Components": [
          { "Waveform": "OMS_RTSM_1", "Signal": "/Control/cmdRoll_rps", "Start-Time": 1, "Scale-Factor": 0.0698132},
          { "Waveform": "OMS_RTSM_2", "Signal": "/Control/cmdPitch_rps", "Start-Time": 1, "Scale-Factor": 0.0174533},
          { "Waveform": "OMS_RTSM_3", "Signal": "/Control/cmdBend_nd", "Start-Time": 1, "Scale-Factor": 0.075}
        ]}
      ]},
      { "Name": "AeroSym1", "Components": [
        { "Level": "Out", "Components": [
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE1L_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE1R_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE3L_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE3R_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdTE5L_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdTE5R_rad", "Start-Time": 1, "Scale-Factor": 0.0349066}
        ]}
      ]},
      { "Name": "AeroAsym1", "Components": [
        { "Level": "Out", "Components": [
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE1L_rad", "Start-Time": 1, "Scale-Factor": 0.0698132},
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE1R_rad", "Start-Time": 1, "Scale-Factor": -0.0698132},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE3L_rad", "Start-Time": 1, "Scale-Factor": 0.0698132},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE3R_rad", "Start-Time": 1, "Scale-Factor": -0.0698132},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdTE5L_rad", "Start-Time": 1, "Scale-Factor": 0.0698132},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdTE5R_rad", "Start-Time": 1, "Scale-Factor": -0.0698132}
        ]}
      ]},
      { "Name": "AeroSym2", "Components": [
        { "Level": "Out", "Components": [
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE2L_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE2R_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE4L_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE4R_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdLEL_rad", "Start-Time": 1, "Scale-Factor": 0.0349066},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdLER_rad", "Start-Time": 1, "Scale-Factor": 0.0349066}
        ]}
      ]},
      { "Name": "AeroAsym2", "Components": [
        { "Level": "Out", "Components": [
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE2L_rad", "Start-Time": 1, "Scale-Factor": 0.0698132},
          { "Waveform": "OMS_Surf_1", "Signal": "/Control/cmdTE2R_rad", "Start-Time": 1, "Scale-Factor": -0.0698132},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE4L_rad", "Start-Time": 1, "Scale-Factor": 0.0698132},
          { "Waveform": "OMS_Surf_2", "Signal": "/Control/cmdTE4R_rad", "Start-Time": 1, "Scale-Factor": -0.0698132},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdLEL_rad", "Start-Time": 1, "Scale-Factor": 0.0698132},
          { "Waveform": "OMS_Surf_3", "Signal": "/Control/cmdLER_rad", "Start-Time": 1, "Scale-Factor": -0.0698132}
        ]}
      ]},
      { "Name": "Bend", "Components": [
        { "Level": "Allocator", "Components": [
          { "Waveform": "SineWave1", "Signal": "/Control/cmdBend_nd", "Start-Time": 1, "Scale-Factor": 1.0}
        ]}
      ]}
    ],

    "OMS_RTSM_1": {"Type": "MultiSine", "Duration": 10.0,
      "Frequency": [0.6283185307179586, 4.360530603182633, 8.092742675647308, 11.824954748111981, 15.557166820576658, 19.28937889304133, 23.021590965506004, 26.753803037970677, 30.486015110435353, 34.21822718290002, 37.9504392553647, 41.682651327829376, 45.414863400294045, 49.14707547275872, 52.8792875452234, 56.61149961768807, 60.34371169015275],
      "Phase": [6.174200357528524, 5.448037839217776, 3.8454607850193847, 1.6650584957876886, 3.9242402680243402, 4.630080151304789, 5.912432865757586, 5.316652321008593, 2.7342570964241117, 6.546636801464082, 8.454702155760696, 8.24574027481253, 8.722410829390709, 7.878019406341706, 5.298703900733216, 7.7365320512089255, 9.81651753182983],
      "Amplitude": [0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396, 0.19810717087274396]
    },
    "OMS_RTSM_2": {"Type": "MultiSine", "Duration": 10.0,
      "Frequency": [1.872389221539517, 5.604601294004191, 9.336813366468867, 13.06902543893354, 16.801237511398217, 20.53344958386289, 24.265661656327563, 27.997873728792232, 31.73008580125691, 35.46229787372159, 39.19450994618626, 42.926722018650935, 46.65893409111561, 50.39114616358028, 54.12335823604496, 57.855570308509634, 61.5877823809743],
      "Phase": [0.11707077907146102, 5.879081252281665, 2.654293566021632, 6.39167677462466, 2.303111141503079, 2.800338003458348, 2.8375030086581976, 1.0089459497629825, 4.815200987699559, 1.6973325623185964, 2.783418143160966, 2.755628470222243, 2.1451236583654723, 6.926060216141984, 3.9516557880470744, 6.20624518523016, 1.2930439886508232],
      "Amplitude": [0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514, 0.22691997229221514]
    },
    "OMS_RTSM_3": {"Type": "MultiSine", "Duration": 10.0,
      "Frequency": [3.1164599123610746, 6.848671984825749, 10.580884057290424, 14.313096129755097, 18.045308202219775, 21.77752027468445, 25.509732347149118, 29.241944419613795, 32.97415649207847, 36.70636856454314, 40.43858063700782, 44.170792709472494, 47.90300478193716, 51.63521685440184, 55.36742892686651, 59.09964099933119, 62.83185307179586],
      "Phase": [6.211686565669407, 5.899844951398339, 3.505168117640797, 6.180092311325341, 8.254160205185341, 8.737306098422593, 9.388424380628422, 8.244859651857812, 5.6682884849905975, 8.788152243105346, 9.847341770112095, 9.543702569226786, 9.4984232787195, 7.611871646984754, 11.38939708047327, 14.142510674662724, 14.85221814913478],
      "Amplitude": [0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345, 0.19694268116397345]
    },

    "OMS_Surf_1": {"Type": "MultiSine", "Duration": 10.0,
      "Frequency": [0.6283185307179586, 4.417269670502012, 8.206220810286066, 11.99517195007012, 15.784123089854173, 19.573074229638227, 23.36202536942228, 27.150976509206327, 30.939927648990384, 34.72887878877444, 38.51782992855849, 42.306781068342545, 46.0957322081266, 49.88468334791065, 53.6736344876947, 57.46258562747876, 61.25153676726281, 65.04048790704685, 68.82943904683091, 72.61839018661497, 76.40734132639902, 80.19629246618307, 83.98524360596713, 87.77419474575119, 91.56314588553523, 95.35209702531928, 99.14104816510334, 102.9299993048874, 106.71895044467145, 110.50790158445552, 114.29685272423957, 118.08580386402362, 121.87475500380768],
      "Phase": [0.7192291741555891, 0.6143212231629689, 5.1063916048525435, 4.658253892040066, 2.1110589485026066, 6.646489147665948, 4.205924320492502, 6.065205101432753, 2.2586922453085823, 3.0062617666733997, 2.882874927921641, 3.604012526571889, 2.8754928814967773, 2.846485557271878, 8.191036648166083, 6.099158352634138, 2.923277384360228, 6.887250676289572, 3.615279031817666, 5.272854146447708, 6.800050163383857, 7.763606224270943, 8.339247615461655, 9.007813392003452, 9.474981985645119, 7.740712729949102, 6.5614691457210155, 9.686495216222504, 6.365757589749245, 9.800394799137994, 10.685686399708327, 7.4915710804230695, 8.3850267098946],
      "Amplitude": [0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556, 0.15131977085149556]
    },
    "OMS_Surf_2": {"Type": "MultiSine", "Duration": 10.0,
      "Frequency": [1.8913022439793097, 5.680253383763363, 9.469204523547416, 13.25815566333147, 17.047106803115522, 20.836057942899576, 24.62500908268363, 28.41396022246768, 32.20291136225173, 35.99186250203579, 39.78081364181984, 43.569764781603894, 47.35871592138795, 51.147667061172, 54.936618200956055, 58.725569340740115, 62.514520480524155, 66.30347162030822, 70.09242276009228, 73.88137389987632, 77.67032503966037, 81.45927617944443, 85.24822731922848, 89.03717845901252, 92.82612959879658, 96.61508073858064, 100.40403187836469, 104.19298301814877, 107.98193415793281, 111.77088529771686, 115.55983643750092, 119.34878757728497, 123.13773871706904],
      "Phase": [0.19247776408559128, 6.742967692149776, 6.399084784686139, 3.9307677574170343, 2.9989112388376924, 7.4029425655035235, 4.669674499047042, 6.5771057155002275, 8.086074401453756, 9.46337021093386, 9.719862932689313, 9.94846642744514, 9.9124190538271, 9.40991601331627, 8.121149720618575, 6.573494872501094, 11.288030317040684, 7.80388298334005, 9.716159537747778, 12.974060679106412, 13.459603288484534, 9.07704224530118, 10.14001775359316, 10.34004331834265, 15.387292012507311, 15.047141754480055, 13.61105664953918, 16.670954550471706, 13.59555705279599, 16.729328863249126, 13.229443625143235, 13.864517432565929, 15.650692394229718],
      "Amplitude": [0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993, 0.16718952780027993]
    },
    "OMS_Surf_3": {"Type": "MultiSine", "Duration": 10.0,
      "Frequency": [3.154285957240661, 6.943237097024714, 10.732188236808769, 14.52113937659282, 18.310090516376874, 22.099041656160928, 25.887992795944978, 29.676943935729035, 33.46589507551308, 37.25484621529714, 41.04379735508119, 44.83274849486524, 48.621699634649296, 52.41065077443336, 56.1996019142174, 59.98855305400146, 63.77750419378551, 67.56645533356956, 71.35540647335361, 75.14435761313767, 78.93330875292173, 82.72225989270578, 86.51121103248983, 90.30016217227389, 94.08911331205795, 97.878064451842, 101.66701559162605, 105.4559667314101, 109.24491787119416, 113.03386901097821, 116.82282015076228, 120.61177129054633, 124.40072243033038],
      "Phase": [0.7025756341387697, 6.12943446621401, 4.275390704790645, 3.1803469809945417, 5.922181189090359, 3.412506097861954, 6.28925076271224, 2.8918611296771477, 5.058879201065271, 4.771648582827999, 5.326484129501341, 5.137929619057949, 4.415737465876501, 2.860283014343797, 1.6225759636344432, 5.703436191923917, 1.6341017695321036, 5.463077924462905, 7.5657493008406576, 3.2249314685316746, 3.914045229698514, 4.055070638766468, 4.6821740241671765, 5.260194354504408, 4.383854469579379, 2.441096295797794, 7.733726704776733, 4.284887379984106, 7.027986656475958, 8.951127858499188, 4.0936405660117146, 6.114911142027206, 6.521848893591844],
      "Amplitude": [0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714, 0.13730805176974714]
    },

    "SineWave1": {"Type": "LinearChirp", "Duration": 6.283185, "Amplitude": [1.0, 1.0], "Frequency": [2.0, 2.0]
    }
  },

  "Mission-Manager": {
    "Fmu-Soc-Switch": {"Source": "/Sensors/Sbus/Channels/0", "Threshold": 0.0, "Gain": 1},
    "Throttle-Safety-Switch": {"Source": "/Sensors/Sbus/Channels/1", "Threshold": 0.33, "Gain": 1},
    "Control-Select-Switch": {"Source": "/Sensors/Sbus/Channels/8", "Threshold": 0.33, "Gain": 1},
    "Test-Increment-Switch": {"Source": "/Sensors/Sbus/Channels/9", "Threshold": 0.33, "Gain": 1},
    "Test-Decrement-Switch": {"Source": "/Sensors/Sbus/Channels/9", "Threshold": 0.33, "Gain": -1},
    "Trigger-Switch": {"Source": "/Sensors/Sbus/Channels/10", "Threshold": 0.0, "Gain": 1},
    "Launch-Switch": {"Source": "/Sensors/Sbus/Channels/11", "Threshold": 0.33, "Gain": -1},
    "Land-Switch": {"Source": "/Sensors/Sbus/Channels/11", "Threshold": 0.33, "Gain": 1},
    "Launch-Controller":"PilotAttitudeLaunch",
    "Baseline-Controller":"PilotAttitudeMan",
    "Land-Controller":"PilotAttitudeLand",

    "Test-Points": [
      { "Test-ID": "0", "Sensor-Processing": "Baseline", "Control": "PilotAttitude26", "Excitation": "Bend"},
      { "Test-ID": "1", "Sensor-Processing": "Baseline", "Control": "PilotAttitude26", "Excitation": "RTSM"},
      { "Test-ID": "2", "Sensor-Processing": "Baseline", "Control": "PilotAttitude26", "Excitation": "AeroSym1"},
      { "Test-ID": "3", "Sensor-Processing": "Baseline", "Control": "PilotAttitude26", "Excitation": "AeroAsym1"},
      { "Test-ID": "4", "Sensor-Processing": "Baseline", "Control": "PilotAttitude26", "Excitation": "AeroSym2"},
      { "Test-ID": "5", "Sensor-Processing": "Baseline", "Control": "PilotAttitude26", "Excitation": "AeroAsym2"},
      { "Test-ID": "6", "Sensor-Processing": "Baseline", "Control": "PilotAttitude29", "Excitation": "Bend"},
      { "Test-ID": "7", "Sensor-Processing": "Baseline", "Control": "PilotAttitude29", "Excitation": "RTSM"},
      { "Test-ID": "8", "Sensor-Processing": "Baseline", "Control": "PilotAttitude29", "Excitation": "AeroSym1"},
      { "Test-ID": "9", "Sensor-Processing": "Baseline", "Control": "PilotAttitude29", "Excitation": "AeroAsym1"},
      { "Test-ID": "10", "Sensor-Processing": "Baseline", "Control": "PilotAttitude29", "Excitation": "AeroSym2"},
      { "Test-ID": "11", "Sensor-Processing": "Baseline", "Control": "PilotAttitude29", "Excitation": "AeroAsym2"}
    ]
  }
}
