diff --git a/controls/documentation/LQR_Design.md b/controls/documentation/LQR_Design.md
new file mode 100644
index 0000000000000000000000000000000000000000..cb1b773fa1e747fe28df60d0265833cb45e5cf98
--- /dev/null
+++ b/controls/documentation/LQR_Design.md
@@ -0,0 +1,129 @@
+# LQR Control
+
+This document describes the MATLAB and Simulink implementation
+for designing an LQR controller for our quadcopter platform.
+This work is almost entirely based on Matt Rich's graduate thesis ([Model development, system identification, and control of a quadrotor helicopter][model_dev]),
+specifically sections 4.1, 4.2 (for the nonlinear model), 7.3 (initial LQR control),
+and 7.4 (improved LQR control).
+
+## 1 Theory
+
+### 1.1 Nonlinear Model
+
+The nonlinear model for the quadcopter is described at a high level in section 4.1,
+with individual components further separated and defined in section 4.2. The definition
+is given in the form of $`\dot \Lambda = f(\Lambda)`$ where $`\Lambda`$ is the state vector.
+Technically, this is also a function of rotor force and torque.
+
+There are 12 state variables: three linear velocities ($`u`$, $`v`$, $`w`$),
+three rotational velocities ($`p`$, $`q`$, $`r`$), hree dimesions for location ($`x`$, $`y`$, $`z`$),
+and three Euler angles ($`\phi`$, $`\theta`$, $`\psi`$).
+
+### 1.2 Linearization
+
+The linearization for this system is performed around the only equilibrium we have, which is hovering in a constant
+position. This means that every state variable is $`0`$ except for possibly the $`z`$ position, but we set that to
+$`0`$ as well because it does not affect the linearization. The equilibrium command inputs are also zero except for
+$`u_T`$ (as some non-zero throttle is required to maintain altitude).
+
+### 1.3 LQR Controller
+
+LQR (Linear Quadratic Regulator) control is designed to minimize a given cost function, which is given as
+```math
+J = \int_0^\infty x^T Q x + u^T R u dt
+```
+where $`x`$ is the error between the state and the equilibrium state, and $`u`$ is the difference between the command
+at time $`t`$ and the equilibrium input. 
+
+## 2 Implementation
+
+### 2.1 Nonlinear Model and Linearization
+
+The nonlinear model, as described in section 4.1, is implemented in MATLAB in `model/linearization.m` with symbolic variables for
+states and commands. Setting all other values to zero, the equilibrium throttle input is found using this model with a binary search
+for the correct command value. The $`A`$ and $`B`$ state-space matrices are determined with symbolic differentiation, so the linearization
+is automatically updated if the model is improved (or simplified) or if the equilibrium point is manually changed.
+
+### 2.2 LQR Controller
+
+Matt Rich describes two different weighting schemes for the matrices $`Q`$ and $`R`$. The first makes each of these matrices diagonal
+(and $`N = 0`$), so the controller tries to separately minimize each of the state variables. The MATLAB function in `model/initial_lqr.m`
+computes this controller when given the state-space matrices $`A`$ and $`B`$, as well as vectors for state values and command values.
+These vectors should correpsond to approximately the maximum allowable value for each state or command (for example, you might set
+the 10th value of the state weights to $`\frac \pi 6`$ if you don't want the quad to pitch more than about $`30^o`$).  
+
+Rich also gives a weighting scheme broken down by what he refers to as subsystems, of which there are four: altitude, lateral,
+longitudinal, and direction. The matrix $`Q`$ then ends up block diagonal (after permutation to make subsystems adjacent).
+The logic behind this is that, for example, if the quad is too far to the right, rolling leftward should reduce the cost rather than
+increase it, because that is the action required to return to equilibrium. Given the $`c`$ and $`d`$ matrices Rich defines in 7.4.2,
+the matlab function in `improved_lqr.m` will construct the corresponding controller for this weighting style. Unfortunately, this design
+has never flown successfully in simulation.
+
+### 2.3 Automated Optimization of LQR Weights
+
+Due to a lack of controls knowledge and intuition in our team, we implemented a MATLAB script to pick weights for the diagonally-weighted
+LQR controller design. The script `repeated_opt.m` picks a random set of weights, then uses MATLAB's included contstrained minimization function
+(`fmincon()`) to search for weights that reduce the actual error when run through the Simulink simulation of the nonlinear model (recall that
+the controller itself was built with only the linearization, so it doesn't represent extreme angles and speeds well). This process is repeated,
+and each set of weights is stored in a file along with a error score (lower implies a better controller).  
+ 
+The function passed to `fmincon()` is `lqr_err()`, which transforms inputs from a subset of the weights to the full weight list and calls the function
+to create the LQR $`K`$ matrix. We assume the lateral and longitudinal weights should be the same, which reduces the dimension of the space for the
+minimization to search to 11 instead of 16. Internally, `lqr_err()` calls `run_once()`, which simply runs the Simulink model and returns the
+error between state and setpoint as the output.  
+
+Warning: The LQR controller designed as above (or in any way) has not been tested on our quadcopter. The simulation is a good place to verify that
+the control conceptually works, but don't assume that it will necessarily act the same way on the quad.
+
+### 2.4 C Implementation
+
+The existing PID controller on the quad is run on the [computation graph][ctrl_graph], which only currently handles scalar values. An implementation
+for matrix constants and matrix multiplication blocks is available on the branch `53-add-lqr-controller-to-c`, but the controller itself is not
+finished or connected. To implement the LQR controller (or any sort of state-feedback style controller) on the quad, either this implementation
+needs to be finished or an entirely new implementation needs to replace the computation graph.
+
+## 3 Errata to "Model Development..."
+
+Like any 150-page technical work, Rich's thesis contains its share of mistakes and errors. Most are minor typos or inconsistencies that largely
+have no impact on the readability or usability of the work. There are a few points, however, that deserve note here to clarify discrepencies
+should anyone want to replicate his work again.  
+
+In section 4.3.1, gravity in the body reference frame should depend on $`\phi`$ rather than $`\psi`$ (roll affects the direction of gravity, but yaw shouldn't).
+The actual vector of graviational force should be
+```math
+^BG = \begin{bmatrix}
+-mg\sin(\theta)\\
+mg\cos(\theta)\sin(\phi)\\
+mg\cos(\theta)\cos(\phi)\\
+\end{bmatrix}
+```  
+
+In section 4.6, the outputs of the camera model should be defined as
+```math
+Y_c[n] = \begin{bmatrix}
+x(nT_c - \tau_c)\\
+\vdots\\
+\psi(nT_c - \tau_c)\\
+\end{bmatrix}
+```
+As written in the original, the actual period was dependent on both the period variable $`T_c`$ and the latency $`\tau_c`$.
+This model is not required for designing a controller, but is necessary if creating a simulation that includes inputs from the camera system.  
+
+In section 7.3.1, the list of weights that Rich chose for his test are missing for $`u`$, $`v`$, $`w`$, $`p`$, $`q`$, and $`r`$, and aren't
+exactly clear for the rest. This was one of the reason for the automated weight testing MATLAB script.
+
+In sections 7.4.2.3 and 7.4.2.4, the $`c`$ matrices should be
+```math
+c_{\text{alt}} = c_{\text{dir}} = \begin{bmatrix}
+1 & 0\\
+0 & \sqrt{10}\\
+0 & 0
+\end{bmatrix}
+```
+in order to create the block-diagonal $`Q`$ given in 7.4.2.4. Also note that this $`Q`$ should be symmetric. The third
+value in the top row of the lateral block is $`0.02`$, and the element symmetric from this one should be $`0.02`$ as
+well, not $`0.2`$. As written, $`Q`$ cannot be used in MATLAB to genenerate a LQR controller because it isn't
+positive semidefinite.  
+
+[model_dev]:   http://lib.dr.iastate.edu/cgi/viewcontent.cgi?article=3777&context=etd
+[ctrl_graph]:  ../../quad/src/computation_graph/README.md
diff --git a/controls/documentation/SimulinkModel.md b/controls/documentation/SimulinkModel.md
index 5deb8593aef0ea67688ed9b7c1554781684efd90..796fd09d34d83cb718841ec1e157880889b4c05d 100644
--- a/controls/documentation/SimulinkModel.md
+++ b/controls/documentation/SimulinkModel.md
@@ -2,7 +2,7 @@
 
 This documentation is about the Simulink model of the quadcopter found in `controls/model/`.
 Specifically, the description and images are from the file
-[`Quadcopter_Model_R2015A.mdl`](../model/Quadcopter_Model_R2015_A.mdl).
+[`Quadcopter_Model.slx`](../model/Quadcopter_Model.slx).
 
 ## 1 Top Level
 
@@ -28,29 +28,60 @@ The variables used at the top level of the model are as follows:
 - $`\frac{d^Bv_0}{dt}`$ - Time derivative of velocity in quadcopter reference frame
 - $`^Bg`$ - Gravity in quadcopter reference frame
 
-The three components are further discussed in the sections below :
+The three components are further discussed in the sections below.
+
+### 1.2 Switches
+
+The top level also contains two toggle swtiches that change the operation of the simulation.
+The left switch toggles between using exact and noisy values for the controls. The
+switch that this toggle controls appears directly above it in the model, and its output is used
+for all but on of the Control System inputs. The right toggle switch changes the simulation from
+using the LQR controller to using the PID, or from PID to LQR. The components that this directly affects
+are all in the Control System block.
 
 ## 2 Control System
 ![Control System Simulink Model][control_sys]
 
-The two central components of the Control System are the Controller and the
+The three central components of the Control System are the two controllers and the
 Signal Mixer.
 
 ### 2.1 Variables
 The variables used in the controls system not listed above are enumerated below:
 
 - $`u_T`$ - Controller output for thrust
-- $`u_A`$ - Controller output for "ailerons", used to control pitch
-- $`u_E`$ - Controller output for "elevators", used to control roll
+- $`u_A`$ - Controller output for "ailerons", used to control roll
+- $`u_E`$ - Controller output for "elevators", used to control pitch
 - $`u_R`$ - Controller output for "rudder", used to control yaw
 
-### 2.2 Controller
-The controller contains the actual PIDs for each element of the setpoint,
-and outputs control values to the signal mixer.
-
-<!---TODO ADR make new doc or write more about controller--->
-
-### 2.3 Signal Mixer
+### 2.2 Controllers
+There are two separate controllers implemented in this subsystem, a PID controller and an LQR controller.
+
+### 2.2.1 PID Controller
+This controller contains the actual PIDs for each element of the setpoint,
+and outputs control values to the signal mixer. The inputs to the signal mixer are
+values for thrust, aileron, throttle, and rudder. Inside the PID Controller block
+are four sets of nested PIDS, one for each of the output commands. For example,
+the $`u_A`$ output is determined by state variables $`y`$, $`v`$, $`\phi`$, and, $`p`$
+(i.e. lateral position, lateral velocity, roll, and roll rate).
+
+### 2.2.2 LQR Controller
+LQR is a state-feedback controller (currently without an observer) that generates
+command outputs directly from the state estimation provided by the sensors.
+The details of the controller and how it is designed can be found in the
+[`LQR_Design.md`](LQR_Design.md) documentation.
+
+### 2.3 Equilibrium inputs
+The result of either controller is added to the equilibrium input before being
+passed to the signal mixer. Equilibrium for this system is when the quadcopter
+is hovering, so $`u_T`$ must be non-zero (all the other commands are zero, however).
+This correction is required for the LQR controller to work. Though not strictly necessary
+for the PID controller, not correcting for equilibrium input would initially respond
+very slowly as the throttle PID loop accumulated its error integration.
+
+### 2.4 Signal Mixer
+Because the output of the controllers is in a style more fit for airplanes or helicopters
+than a quadrotor, we need to convert the control result values to something meaningful
+to control our flight with.
 The Signal Mixer is simply a $`4 \times 4`$ matrix that is multiplied by the vector
 $`\begin{pmatrix}u_T & u_A & u_E & u_R\end{pmatrix}^\top`$ to produce a vector
 of PWM commands for the motor. As such, each row of the matrix corresponds to one
@@ -65,9 +96,11 @@ S = \left(\begin{array}{rrrr}
 ```
 For example, the fourth column is $`\begin{pmatrix}-1 & 1 & 1 & -1\end{pmatrix}^\top`$,
 so when the controller commands a positive rudder (i.e. positive change in yaw),
-the speed of rotors 1 and 4 decrease and 2 and 3 increase.
+the speed of rotors 1 and 4 decrease and 2 and 3 increase. 
 
-<!---TODO ADR The matrix is copied from MATLAB, but that example can't be right--->
+When comparing different research or implementations, be careful to compare signal mixing
+matrices. Everyone has their own scheme for number the rotors and orienting the quad,
+but the signal mixer should give enough information to determine the rotor configuration.
 
 ## 3 Actuation
 ![Actuation Simulink Model][act_sys]
@@ -127,6 +160,9 @@ phase), sample, quantize, and delay their readings.
 Without these, the Simulink model would only be good to prove math, and would not
 actually provide valuable insight into the physical system.
 
+The 3D Graphical Simulation block can be opened to geive a simple visualization of
+the quad's flight.
+
 ### 4.1 Variables
 There are no new quantities that haven't already been explained in a previous section.
 
@@ -135,8 +171,8 @@ A good resource to better understand the mathematical process of this model can
 in Matthew Rich's 2012 thesis,
 [Model development, system identification, and control of a quadrotor helicopter][model_dev].
 
-[top_level]:   ../../documentation/images/simulink_top_level.png
-[control_sys]: ../../documentation/images/simulink_control_sys.png
+[top_level]:   ../../documentation/images/simulink_lqr_top.png
+[control_sys]: ../../documentation/images/simulink_lqr_control.png
 [act_sys]:     ../../documentation/images/simulink_act_sys.png
-[sensor_sys]:  ../../documentation/images/simulink_sensor_sys.png
+[sensor_sys]:  ../../documentation/images/simulink_lqr_sensor.png
 [model_dev]:   http://lib.dr.iastate.edu/cgi/viewcontent.cgi?article=3777&context=etd
diff --git a/controls/model/Quadcopter_Model.slx b/controls/model/Quadcopter_Model.slx
new file mode 100644
index 0000000000000000000000000000000000000000..e7f7ad3500d97b1b851d355dcadb8fac2467ade9
Binary files /dev/null and b/controls/model/Quadcopter_Model.slx differ
diff --git a/controls/model/Quadcopter_Model_R2015_A.mdl b/controls/model/Quadcopter_Model_R2015_A.mdl
deleted file mode 100644
index dc185578f51fa469a8f1b8fb5900bf19a33b89bc..0000000000000000000000000000000000000000
--- a/controls/model/Quadcopter_Model_R2015_A.mdl
+++ /dev/null
@@ -1,17773 +0,0 @@
-Model {
-  Name			  "Quadcopter_Model_R2015_A"
-  Version		  8.5
-  SavedCharacterEncoding  "windows-1252"
-  GraphicalInterface {
-    NumRootInports	    0
-    NumRootOutports	    0
-    ParameterArgumentNames  ""
-    ComputedModelVersion    "1.2982"
-    NumModelReferences	    0
-    NumTestPointedSignals   0
-  }
-  ScopeRefreshTime	  0.035000
-  OverrideScopeRefreshTime on
-  DisableAllScopes	  off
-  DataTypeOverride	  "UseLocalSettings"
-  DataTypeOverrideAppliesTo "AllNumericTypes"
-  MinMaxOverflowLogging	  "UseLocalSettings"
-  MinMaxOverflowArchiveMode "Overwrite"
-  FPTRunName		  "Run 1"
-  MaxMDLFileLineLength	  120
-  InitFcn		  "clear mex\ndelete test_model_sfun.mexw64"
-  Object {
-    $PropName		    "BdWindowsInfo"
-    $ObjectID		    1
-    $ClassName		    "Simulink.BDWindowsInfo"
-    Object {
-      $PropName		      "WindowsInfo"
-      $ObjectID		      2
-      $ClassName	      "Simulink.WindowInfo"
-      IsActive		      [1]
-      Location		      [-8.0, -8.0, 1936.0, 1056.0]
-      Object {
-	$PropName		"ModelBrowserInfo"
-	$ObjectID		3
-	$ClassName		"Simulink.ModelBrowserInfo"
-	Visible			[0]
-	DockPosition		"Left"
-	Width			[50]
-	Height			[50]
-	Filter			[9]
-      }
-      Object {
-	$PropName		"ExplorerBarInfo"
-	$ObjectID		4
-	$ClassName		"Simulink.ExplorerBarInfo"
-	Visible			[0]
-      }
-      Array {
-	Type			"Simulink.EditorInfo"
-	Dimension		4
-	Object {
-	  $ObjectID		  5
-	  IsActive		  [0]
-	  ViewObjType		  "SimulinkTopLevel"
-	  LoadSaveID		  "0"
-	  Extents		  [1755.0, 904.0]
-	  ZoomFactor		  [1.0]
-	  Offset		  [336.19666666666762, 144.20000000000005]
-	}
-	Object {
-	  $ObjectID		  6
-	  IsActive		  [1]
-	  ViewObjType		  "SimulinkSubsys"
-	  LoadSaveID		  "573"
-	  Extents		  [1755.0, 904.0]
-	  ZoomFactor		  [0.8]
-	  Offset		  [-151.38571428571572, -12.602379760288613]
-	}
-	Object {
-	  $ObjectID		  7
-	  IsActive		  [0]
-	  ViewObjType		  "SimulinkSubsys"
-	  LoadSaveID		  "650"
-	  Extents		  [1755.0, 904.0]
-	  ZoomFactor		  [0.5]
-	  Offset		  [383.52935415893444, -40.361112608789426]
-	}
-	Object {
-	  $ObjectID		  8
-	  IsActive		  [0]
-	  ViewObjType		  "SimulinkSubsys"
-	  LoadSaveID		  "436"
-	  Extents		  [1755.0, 904.0]
-	  ZoomFactor		  [1.25]
-	  Offset		  [716.49880952381045, 116.5285714285709]
-	}
-	PropName		"EditorsInfo"
-      }
-    }
-  }
-  Created		  "Thu Nov 03 18:34:52 2016"
-  Creator		  "Andy"
-  UpdateHistory		  "UpdateHistoryNever"
-  ModifiedByFormat	  "%<Auto>"
-  LastModifiedBy	  "Andy"
-  ModifiedDateFormat	  "%<Auto>"
-  LastModifiedDate	  "Tue Apr 04 18:41:22 2017"
-  RTWModifiedTimeStamp	  413232081
-  ModelVersionFormat	  "1.%<AutoIncrement:2982>"
-  ConfigurationManager	  "none"
-  SampleTimeColors	  on
-  SampleTimeAnnotations	  off
-  LibraryLinkDisplay	  "disabled"
-  WideLines		  off
-  ShowLineDimensions	  on
-  ShowPortDataTypes	  off
-  ShowDesignRanges	  off
-  ShowLoopsOnError	  on
-  IgnoreBidirectionalLines off
-  ShowStorageClass	  off
-  ShowTestPointIcons	  on
-  ShowSignalResolutionIcons on
-  ShowViewerIcons	  on
-  SortedOrder		  off
-  ExecutionContextIcon	  off
-  ShowLinearizationAnnotations on
-  ShowMarkup		  on
-  BlockNameDataTip	  off
-  BlockParametersDataTip  off
-  BlockDescriptionStringDataTip	off
-  ToolBar		  on
-  StatusBar		  on
-  BrowserShowLibraryLinks off
-  BrowserLookUnderMasks	  off
-  SimulationMode	  "normal"
-  PauseTimes		  "5"
-  NumberOfSteps		  1
-  SnapshotBufferSize	  10
-  SnapshotInterval	  10
-  NumberOfLastSnapshots	  0
-  LinearizationMsg	  "none"
-  Profile		  off
-  ParamWorkspaceSource	  "MATLABWorkspace"
-  AccelSystemTargetFile	  "accel.tlc"
-  AccelTemplateMakefile	  "accel_default_tmf"
-  AccelMakeCommand	  "make_rtw"
-  TryForcingSFcnDF	  off
-  Object {
-    $PropName		    "DataLoggingOverride"
-    $ObjectID		    10
-    $ClassName		    "Simulink.SimulationData.ModelLoggingInfo"
-    model_		    "Quadcopter_Model_R2015_A"
-    overrideMode_	    [0.0]
-    Array {
-      Type		      "Cell"
-      Dimension		      1
-      Cell		      "Quadcopter_Model_R2015_A"
-      PropName		      "logAsSpecifiedByModels_"
-    }
-    Array {
-      Type		      "Cell"
-      Dimension		      1
-      Cell		      []
-      PropName		      "logAsSpecifiedByModelsSSIDs_"
-    }
-  }
-  RecordCoverage	  off
-  CovPath		  "/"
-  CovSaveName		  "covdata"
-  CovMetricSettings	  "dwe"
-  CovNameIncrementing	  off
-  CovHtmlReporting	  off
-  CovForceBlockReductionOff on
-  CovEnableCumulative	  on
-  covSaveCumulativeToWorkspaceVar off
-  CovSaveSingleToWorkspaceVar off
-  CovCumulativeVarName	  "covCumulativeData"
-  CovCumulativeReport	  off
-  CovReportOnPause	  on
-  CovModelRefEnable	  "Off"
-  CovExternalEMLEnable	  on
-  CovSFcnEnable		  on
-  CovBoundaryAbsTol	  0.000010
-  CovBoundaryRelTol	  0.010000
-  CovUseTimeInterval	  off
-  CovStartTime		  0
-  CovStopTime		  0
-  ExtModeBatchMode	  off
-  ExtModeEnableFloating	  on
-  ExtModeTrigType	  "manual"
-  ExtModeTrigMode	  "normal"
-  ExtModeTrigPort	  "1"
-  ExtModeTrigElement	  "any"
-  ExtModeTrigDuration	  1000
-  ExtModeTrigDurationFloating "auto"
-  ExtModeTrigHoldOff	  0
-  ExtModeTrigDelay	  0
-  ExtModeTrigDirection	  "rising"
-  ExtModeTrigLevel	  0
-  ExtModeArchiveMode	  "off"
-  ExtModeAutoIncOneShot	  off
-  ExtModeIncDirWhenArm	  off
-  ExtModeAddSuffixToVar	  off
-  ExtModeWriteAllDataToWs off
-  ExtModeArmWhenConnect	  on
-  ExtModeSkipDownloadWhenConnect off
-  ExtModeLogAll		  on
-  ExtModeAutoUpdateStatusClock on
-  ShowModelReferenceBlockVersion off
-  ShowModelReferenceBlockIO off
-  Array {
-    Type		    "Handle"
-    Dimension		    1
-    Simulink.ConfigSet {
-      $ObjectID		      11
-      Version		      "1.15.0"
-      Array {
-	Type			"Handle"
-	Dimension		8
-	Simulink.SolverCC {
-	  $ObjectID		  12
-	  Version		  "1.15.0"
-	  StartTime		  "0.0"
-	  StopTime		  "runtime"
-	  AbsTol		  "auto"
-	  FixedStep		  "auto"
-	  InitialStep		  "auto"
-	  MaxNumMinSteps	  "-1"
-	  MaxOrder		  5
-	  ZcThreshold		  "auto"
-	  ConsecutiveZCsStepRelTol "10*128*eps"
-	  MaxConsecutiveZCs	  "1000"
-	  ExtrapolationOrder	  4
-	  NumberNewtonIterations  1
-	  MaxStep		  "auto"
-	  MinStep		  "auto"
-	  MaxConsecutiveMinStep	  "1"
-	  RelTol		  "1e-3"
-	  SolverMode		  "SingleTasking"
-	  EnableConcurrentExecution off
-	  ConcurrentTasks	  off
-	  Solver		  ode45
-	  SolverName		  ode45
-	  SolverJacobianMethodControl "auto"
-	  ShapePreserveControl	  "DisableAll"
-	  ZeroCrossControl	  "UseLocalSettings"
-	  ZeroCrossAlgorithm	  "Nonadaptive"
-	  AlgebraicLoopSolver	  "TrustRegion"
-	  SolverResetMethod	  "Fast"
-	  PositivePriorityOrder	  off
-	  AutoInsertRateTranBlk	  off
-	  SampleTimeConstraint	  "Unconstrained"
-	  InsertRTBMode		  "Whenever possible"
-	}
-	Simulink.DataIOCC {
-	  $ObjectID		  13
-	  Version		  "1.15.0"
-	  Decimation		  "1"
-	  ExternalInput		  "[t, u]"
-	  FinalStateName	  "xFinal"
-	  InitialState		  "xInitial"
-	  LimitDataPoints	  off
-	  MaxDataPoints		  "1000"
-	  LoadExternalInput	  off
-	  LoadInitialState	  off
-	  SaveFinalState	  off
-	  SaveCompleteFinalSimState off
-	  SaveFormat		  "Dataset"
-	  SignalLoggingSaveFormat "Dataset"
-	  SaveOutput		  on
-	  SaveState		  off
-	  SignalLogging		  on
-	  DSMLogging		  on
-	  InspectSignalLogs	  off
-	  VisualizeSimOutput	  on
-	  SaveTime		  on
-	  ReturnWorkspaceOutputs  off
-	  StateSaveName		  "xout"
-	  TimeSaveName		  "tout"
-	  OutputSaveName	  "yout"
-	  SignalLoggingName	  "logsout"
-	  DSMLoggingName	  "dsmout"
-	  OutputOption		  "RefineOutputTimes"
-	  OutputTimes		  "[]"
-	  ReturnWorkspaceOutputsName "out"
-	  Refine		  "1"
-	}
-	Simulink.OptimizationCC {
-	  $ObjectID		  14
-	  Version		  "1.15.0"
-	  Array {
-	    Type		    "Cell"
-	    Dimension		    8
-	    Cell		    "BooleansAsBitfields"
-	    Cell		    "PassReuseOutputArgsAs"
-	    Cell		    "PassReuseOutputArgsThreshold"
-	    Cell		    "ZeroExternalMemoryAtStartup"
-	    Cell		    "ZeroInternalMemoryAtStartup"
-	    Cell		    "OptimizeModelRefInitCode"
-	    Cell		    "NoFixptDivByZeroProtection"
-	    Cell		    "UseSpecifiedMinMax"
-	    PropName		    "DisabledProps"
-	  }
-	  BlockReduction	  on
-	  BooleanDataType	  on
-	  ConditionallyExecuteInputs on
-	  InlineParams		  off
-	  UseDivisionForNetSlopeComputation "off"
-	  UseFloatMulNetSlope	  off
-	  DefaultUnderspecifiedDataType	"double"
-	  UseSpecifiedMinMax	  off
-	  InlineInvariantSignals  off
-	  OptimizeBlockIOStorage  on
-	  BufferReuse		  on
-	  EnhancedBackFolding	  off
-	  CachingGlobalReferences off
-	  GlobalBufferReuse	  on
-	  StrengthReduction	  off
-	  ExpressionFolding	  on
-	  BooleansAsBitfields	  off
-	  BitfieldContainerType	  "uint_T"
-	  EnableMemcpy		  on
-	  MemcpyThreshold	  64
-	  PassReuseOutputArgsAs	  "Structure reference"
-	  PassReuseOutputArgsThreshold 12
-	  ExpressionDepthLimit	  128
-	  LocalBlockOutputs	  on
-	  RollThreshold		  5
-	  StateBitsets		  off
-	  DataBitsets		  off
-	  ActiveStateOutputEnumStorageType "Native Integer"
-	  ZeroExternalMemoryAtStartup on
-	  ZeroInternalMemoryAtStartup on
-	  InitFltsAndDblsToZero	  off
-	  NoFixptDivByZeroProtection off
-	  EfficientFloat2IntCast  off
-	  EfficientMapNaN2IntZero on
-	  OptimizeModelRefInitCode off
-	  LifeSpan		  "inf"
-	  MaxStackSize		  "Inherit from target"
-	  BufferReusableBoundary  on
-	  SimCompilerOptimization "off"
-	  AccelVerboseBuild	  off
-	}
-	Simulink.DebuggingCC {
-	  $ObjectID		  15
-	  Version		  "1.15.0"
-	  RTPrefix		  "error"
-	  ConsistencyChecking	  "none"
-	  ArrayBoundsChecking	  "none"
-	  SignalInfNanChecking	  "none"
-	  SignalRangeChecking	  "none"
-	  ReadBeforeWriteMsg	  "UseLocalSettings"
-	  WriteAfterWriteMsg	  "UseLocalSettings"
-	  WriteAfterReadMsg	  "UseLocalSettings"
-	  AlgebraicLoopMsg	  "error"
-	  ArtificialAlgebraicLoopMsg "warning"
-	  SaveWithDisabledLinksMsg "warning"
-	  SaveWithParameterizedLinksMsg	"warning"
-	  CheckSSInitialOutputMsg on
-	  UnderspecifiedInitializationDetection	"Simplified"
-	  MergeDetectMultiDrivingBlocksExec "error"
-	  CheckExecutionContextPreStartOutputMsg off
-	  CheckExecutionContextRuntimeOutputMsg	off
-	  SignalResolutionControl "UseLocalSettings"
-	  BlockPriorityViolationMsg "warning"
-	  MinStepSizeMsg	  "warning"
-	  TimeAdjustmentMsg	  "none"
-	  MaxConsecutiveZCsMsg	  "error"
-	  MaskedZcDiagnostic	  "warning"
-	  IgnoredZcDiagnostic	  "warning"
-	  SolverPrmCheckMsg	  "none"
-	  InheritedTsInSrcMsg	  "warning"
-	  MultiTaskDSMMsg	  "error"
-	  MultiTaskCondExecSysMsg "error"
-	  MultiTaskRateTransMsg	  "error"
-	  SingleTaskRateTransMsg  "none"
-	  TasksWithSamePriorityMsg "warning"
-	  SigSpecEnsureSampleTimeMsg "warning"
-	  CheckMatrixSingularityMsg "none"
-	  IntegerOverflowMsg	  "warning"
-	  Int32ToFloatConvMsg	  "warning"
-	  ParameterDowncastMsg	  "error"
-	  ParameterOverflowMsg	  "error"
-	  ParameterUnderflowMsg	  "none"
-	  ParameterPrecisionLossMsg "warning"
-	  ParameterTunabilityLossMsg "warning"
-	  FixptConstUnderflowMsg  "none"
-	  FixptConstOverflowMsg	  "none"
-	  FixptConstPrecisionLossMsg "none"
-	  UnderSpecifiedDataTypeMsg "none"
-	  UnnecessaryDatatypeConvMsg "none"
-	  VectorMatrixConversionMsg "none"
-	  InvalidFcnCallConnMsg	  "error"
-	  FcnCallInpInsideContextMsg "EnableAllAsError"
-	  SignalLabelMismatchMsg  "none"
-	  UnconnectedInputMsg	  "warning"
-	  UnconnectedOutputMsg	  "warning"
-	  UnconnectedLineMsg	  "warning"
-	  SFcnCompatibilityMsg	  "none"
-	  FrameProcessingCompatibilityMsg "error"
-	  UniqueDataStoreMsg	  "none"
-	  BusObjectLabelMismatch  "warning"
-	  RootOutportRequireBusObject "warning"
-	  AssertControl		  "UseLocalSettings"
-	  ModelReferenceIOMsg	  "none"
-	  ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error"
-	  ModelReferenceVersionMismatchMessage "none"
-	  ModelReferenceIOMismatchMessage "none"
-	  UnknownTsInhSupMsg	  "warning"
-	  ModelReferenceDataLoggingMessage "warning"
-	  ModelReferenceSymbolNameMessage "warning"
-	  ModelReferenceExtraNoncontSigs "error"
-	  StateNameClashWarn	  "none"
-	  SimStateInterfaceChecksumMismatchMsg "warning"
-	  SimStateOlderReleaseMsg "error"
-	  InitInArrayFormatMsg	  "warning"
-	  StrictBusMsg		  "ErrorLevel1"
-	  BusNameAdapt		  "WarnAndRepair"
-	  NonBusSignalsTreatedAsBus "none"
-	  BlockIODiagnostic	  "none"
-	  SFUnusedDataAndEventsDiag "warning"
-	  SFUnexpectedBacktrackingDiag "error"
-	  SFInvalidInputDataAccessInChartInitDiag "warning"
-	  SFNoUnconditionalDefaultTransitionDiag "error"
-	  SFTransitionOutsideNaturalParentDiag "warning"
-	  SFUnconditionalTransitionShadowingDiag "warning"
-	  SFUndirectedBroadcastEventsDiag "warning"
-	  SFTransitionActionBeforeConditionDiag	"warning"
-	  SFOutputUsedAsStateInMooreChartDiag "error"
-	  IntegerSaturationMsg	  "warning"
-	}
-	Simulink.HardwareCC {
-	  $ObjectID		  16
-	  Version		  "1.15.0"
-	  ProdBitPerChar	  8
-	  ProdBitPerShort	  16
-	  ProdBitPerInt		  32
-	  ProdBitPerLong	  32
-	  ProdBitPerLongLong	  64
-	  ProdBitPerFloat	  32
-	  ProdBitPerDouble	  64
-	  ProdBitPerPointer	  64
-	  ProdLargestAtomicInteger "Char"
-	  ProdLargestAtomicFloat  "Float"
-	  ProdIntDivRoundTo	  "Zero"
-	  ProdEndianess		  "LittleEndian"
-	  ProdWordSize		  32
-	  ProdShiftRightIntArith  on
-	  ProdLongLongMode	  off
-	  ProdHWDeviceType	  "Specified"
-	  TargetBitPerChar	  8
-	  TargetBitPerShort	  16
-	  TargetBitPerInt	  32
-	  TargetBitPerLong	  32
-	  TargetBitPerLongLong	  64
-	  TargetBitPerFloat	  32
-	  TargetBitPerDouble	  64
-	  TargetBitPerPointer	  32
-	  TargetLargestAtomicInteger "Char"
-	  TargetLargestAtomicFloat "None"
-	  TargetShiftRightIntArith on
-	  TargetLongLongMode	  off
-	  TargetIntDivRoundTo	  "Undefined"
-	  TargetEndianess	  "Unspecified"
-	  TargetWordSize	  32
-	  TargetPreprocMaxBitsSint 32
-	  TargetPreprocMaxBitsUint 32
-	  TargetHWDeviceType	  "Specified"
-	  TargetUnknown		  off
-	  ProdEqTarget		  on
-	}
-	Simulink.ModelReferenceCC {
-	  $ObjectID		  17
-	  Version		  "1.15.0"
-	  UpdateModelReferenceTargets "Force"
-	  CheckModelReferenceTargetMessage "error"
-	  EnableParallelModelReferenceBuilds off
-	  ParallelModelReferenceErrorOnInvalidPool on
-	  ParallelModelReferenceMATLABWorkerInit "None"
-	  ModelReferenceNumInstancesAllowed "Multi"
-	  PropagateVarSize	  "Infer from blocks in model"
-	  ModelReferencePassRootInputsByReference on
-	  ModelReferenceMinAlgLoopOccurrences off
-	  PropagateSignalLabelsOutOfModel on
-	  SupportModelReferenceSimTargetCustomCode off
-	}
-	Simulink.SFSimCC {
-	  $ObjectID		  18
-	  Version		  "1.15.0"
-	  SimCustomHeaderCode	  "#include \"complementary_filter.h\"\n#include \"aeb_mat.h\"\n#include \"angle_accel.h\""
-	  SimUserSources	  "complementary_filter.c\naeb_mat.c\nangle_accel.c"
-	  SimUserIncludeDirs	  "../../quad/src/computation_graph\n../../quad/src/quad_app\n../../quad/src/graph_blocks\n../.."
-	  "/quad/src/commands"
-	  SFSimEcho		  on
-	  SimCtrlC		  on
-	  SimIntegrity		  on
-	  SimUseLocalCustomCode	  off
-	  SimParseCustomCode	  on
-	  SimBuildMode		  "sf_incremental_build"
-	  SimGenImportedTypeDefs  off
-	}
-	Simulink.RTWCC {
-	  $BackupClass		  "Simulink.RTWCC"
-	  $ObjectID		  19
-	  Version		  "1.15.0"
-	  Array {
-	    Type		    "Cell"
-	    Dimension		    13
-	    Cell		    "IncludeHyperlinkInReport"
-	    Cell		    "GenerateTraceInfo"
-	    Cell		    "GenerateTraceReport"
-	    Cell		    "GenerateTraceReportSl"
-	    Cell		    "GenerateTraceReportSf"
-	    Cell		    "GenerateTraceReportEml"
-	    Cell		    "PortableWordSizes"
-	    Cell		    "GenerateWebview"
-	    Cell		    "GenerateCodeMetricsReport"
-	    Cell		    "GenerateCodeReplacementReport"
-	    Cell		    "GenerateMissedCodeReplacementReport"
-	    Cell		    "GenerateErtSFunction"
-	    Cell		    "CreateSILPILBlock"
-	    PropName		    "DisabledProps"
-	  }
-	  SystemTargetFile	  "grt.tlc"
-	  TLCOptions		  ""
-	  GenCodeOnly		  off
-	  MakeCommand		  "make_rtw"
-	  GenerateMakefile	  on
-	  PackageGeneratedCodeAndArtifacts off
-	  TemplateMakefile	  "grt_default_tmf"
-	  PostCodeGenCommand	  ""
-	  GenerateReport	  off
-	  SaveLog		  off
-	  RTWVerbose		  on
-	  RetainRTWFile		  off
-	  ProfileTLC		  off
-	  TLCDebug		  off
-	  TLCCoverage		  off
-	  TLCAssert		  off
-	  RTWUseLocalCustomCode	  off
-	  RTWUseSimCustomCode	  off
-	  Toolchain		  "MinGW64 v4.x | gmake (64-bit Windows)"
-	  BuildConfiguration	  "Faster Builds"
-	  IncludeHyperlinkInReport off
-	  LaunchReport		  off
-	  PortableWordSizes	  off
-	  CreateSILPILBlock	  "None"
-	  CodeExecutionProfiling  off
-	  CodeExecutionProfileVariable "executionProfile"
-	  CodeProfilingSaveOptions "SummaryOnly"
-	  CodeProfilingInstrumentation off
-	  SILDebugging		  off
-	  TargetLang		  "C"
-	  IncludeBusHierarchyInRTWFileBlockHierarchyMap	off
-	  GenerateTraceInfo	  off
-	  GenerateTraceReport	  off
-	  GenerateTraceReportSl	  off
-	  GenerateTraceReportSf	  off
-	  GenerateTraceReportEml  off
-	  GenerateWebview	  off
-	  GenerateCodeMetricsReport off
-	  GenerateCodeReplacementReport	off
-	  GenerateMissedCodeReplacementReport off
-	  RTWCompilerOptimization "off"
-	  RTWCustomCompilerOptimizations ""
-	  CheckMdlBeforeBuild	  "Off"
-	  SharedConstantsCachingThreshold 1024
-	  Array {
-	    Type		    "Handle"
-	    Dimension		    2
-	    Simulink.CodeAppCC {
-	      $ObjectID		      20
-	      Version		      "1.15.0"
-	      Array {
-		Type			"Cell"
-		Dimension		25
-		Cell			"IgnoreCustomStorageClasses"
-		Cell			"IgnoreTestpoints"
-		Cell			"InsertBlockDesc"
-		Cell			"InsertPolySpaceComments"
-		Cell			"SFDataObjDesc"
-		Cell			"MATLABFcnDesc"
-		Cell			"SimulinkDataObjDesc"
-		Cell			"DefineNamingRule"
-		Cell			"SignalNamingRule"
-		Cell			"ParamNamingRule"
-		Cell			"InternalIdentifier"
-		Cell			"InlinedPrmAccess"
-		Cell			"CustomSymbolStr"
-		Cell			"CustomSymbolStrGlobalVar"
-		Cell			"CustomSymbolStrType"
-		Cell			"CustomSymbolStrField"
-		Cell			"CustomSymbolStrFcn"
-		Cell			"CustomSymbolStrModelFcn"
-		Cell			"CustomSymbolStrFcnArg"
-		Cell			"CustomSymbolStrBlkIO"
-		Cell			"CustomSymbolStrTmpVar"
-		Cell			"CustomSymbolStrMacro"
-		Cell			"CustomSymbolStrUtil"
-		Cell			"CustomUserTokenString"
-		Cell			"ReqsInCode"
-		PropName		"DisabledProps"
-	      }
-	      ForceParamTrailComments off
-	      GenerateComments	      on
-	      CommentStyle	      "Auto"
-	      IgnoreCustomStorageClasses on
-	      IgnoreTestpoints	      off
-	      IncHierarchyInIds	      off
-	      MaxIdLength	      31
-	      PreserveName	      off
-	      PreserveNameWithParent  off
-	      ShowEliminatedStatement off
-	      OperatorAnnotations     off
-	      IncAutoGenComments      off
-	      SimulinkDataObjDesc     off
-	      SFDataObjDesc	      off
-	      MATLABFcnDesc	      off
-	      IncDataTypeInIds	      off
-	      MangleLength	      1
-	      CustomSymbolStrGlobalVar "$R$N$M"
-	      CustomSymbolStrType     "$N$R$M_T"
-	      CustomSymbolStrField    "$N$M"
-	      CustomSymbolStrFcn      "$R$N$M$F"
-	      CustomSymbolStrFcnArg   "rt$I$N$M"
-	      CustomSymbolStrBlkIO    "rtb_$N$M"
-	      CustomSymbolStrTmpVar   "$N$M"
-	      CustomSymbolStrMacro    "$R$N$M"
-	      CustomSymbolStrUtil     "$N$C"
-	      DefineNamingRule	      "None"
-	      ParamNamingRule	      "None"
-	      SignalNamingRule	      "None"
-	      InsertBlockDesc	      off
-	      InsertPolySpaceComments off
-	      SimulinkBlockComments   on
-	      MATLABSourceComments    off
-	      EnableCustomComments    off
-	      InternalIdentifier      "Shortened"
-	      InlinedPrmAccess	      "Literals"
-	      ReqsInCode	      off
-	      UseSimReservedNames     off
-	    }
-	    Simulink.GRTTargetCC {
-	      $BackupClass	      "Simulink.TargetCC"
-	      $ObjectID		      21
-	      Version		      "1.15.0"
-	      Array {
-		Type			"Cell"
-		Dimension		15
-		Cell			"IncludeMdlTerminateFcn"
-		Cell			"SuppressErrorStatus"
-		Cell			"ERTCustomFileBanners"
-		Cell			"GenerateSampleERTMain"
-		Cell			"ExistingSharedCode"
-		Cell			"GenerateTestInterfaces"
-		Cell			"ModelStepFunctionPrototypeControlCompliant"
-		Cell			"GenerateAllocFcn"
-		Cell			"PurelyIntegerCode"
-		Cell			"SupportComplex"
-		Cell			"SupportAbsoluteTime"
-		Cell			"SupportContinuousTime"
-		Cell			"SupportNonInlinedSFcns"
-		Cell			"RemoveDisableFunc"
-		Cell			"RemoveResetFunc"
-		PropName		"DisabledProps"
-	      }
-	      TargetFcnLib	      "ansi_tfl_table_tmw.mat"
-	      TargetLibSuffix	      ""
-	      TargetPreCompLibLocation ""
-	      GenFloatMathFcnCalls    "NOT IN USE"
-	      TargetLangStandard      "C99 (ISO)"
-	      CodeReplacementLibrary  "None"
-	      UtilityFuncGeneration   "Auto"
-	      ERTMultiwordTypeDef     "System defined"
-	      ERTMultiwordLength      256
-	      MultiwordLength	      2048
-	      GenerateFullHeader      on
-	      InferredTypesCompatibility off
-	      GenerateSampleERTMain   off
-	      GenerateTestInterfaces  off
-	      ModelReferenceCompliant on
-	      ParMdlRefBuildCompliant on
-	      CompOptLevelCompliant   on
-	      ConcurrentExecutionCompliant on
-	      IncludeMdlTerminateFcn  on
-	      GeneratePreprocessorConditionals "Use local settings"
-	      CombineOutputUpdateFcns on
-	      CombineSignalStateStructs	off
-	      SuppressErrorStatus     off
-	      ERTFirstTimeCompliant   off
-	      IncludeFileDelimiter    "Auto"
-	      ERTCustomFileBanners    off
-	      SupportAbsoluteTime     on
-	      LogVarNameModifier      "rt_"
-	      MatFileLogging	      on
-	      MultiInstanceERTCode    off
-	      CodeInterfacePackaging  "Nonreusable function"
-	      SupportNonFinite	      on
-	      SupportComplex	      on
-	      PurelyIntegerCode	      off
-	      SupportContinuousTime   on
-	      SupportNonInlinedSFcns  on
-	      SupportVariableSizeSignals off
-	      ParenthesesLevel	      "Nominal"
-	      CastingMode	      "Nominal"
-	      MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization"
-	      ModelStepFunctionPrototypeControlCompliant off
-	      CPPClassGenCompliant    on
-	      AutosarCompliant	      off
-	      GRTInterface	      off
-	      GenerateAllocFcn	      off
-	      GenerateSharedConstants on
-	      UseMalloc		      off
-	      ExtMode		      off
-	      ExtModeStaticAlloc      off
-	      ExtModeTesting	      off
-	      ExtModeStaticAllocSize  1000000
-	      ExtModeTransport	      0
-	      ExtModeMexFile	      "ext_comm"
-	      ExtModeIntrfLevel	      "Level1"
-	      RTWCAPISignals	      off
-	      RTWCAPIParams	      off
-	      RTWCAPIStates	      off
-	      RTWCAPIRootIO	      off
-	      GenerateASAP2	      off
-	      MultiInstanceErrorCode  "Error"
-	    }
-	    PropName		    "Components"
-	  }
-	}
-	PropName		"Components"
-      }
-      Name		      "Configuration"
-      CurrentDlgPage	      "Solver"
-      ConfigPrmDlgPosition    [ 510, 71, 1400, 811 ]  
-    }
-    PropName		    "ConfigurationSets"
-  }
-  Simulink.ConfigSet {
-    $PropName		    "ActiveConfigurationSet"
-    $ObjectID		    11
-  }
-  Object {
-    $PropName		    "DataTransfer"
-    $ObjectID		    23
-    $ClassName		    "Simulink.GlobalDataTransfer"
-    DefaultTransitionBetweenSyncTasks "Ensure deterministic transfer (maximum delay)"
-    DefaultTransitionBetweenAsyncTasks "Ensure data integrity only"
-    DefaultTransitionBetweenContTasks "Ensure deterministic transfer (minimum delay)"
-    DefaultExtrapolationMethodBetweenContTasks "None"
-    AutoInsertRateTranBlk   [0]
-  }
-  ExplicitPartitioning	  off
-  BlockDefaults {
-    ForegroundColor	    "black"
-    BackgroundColor	    "white"
-    DropShadow		    off
-    NamePlacement	    "normal"
-    FontName		    "Helvetica"
-    FontSize		    10
-    FontWeight		    "normal"
-    FontAngle		    "normal"
-    ShowName		    on
-    BlockRotation	    0
-    BlockMirror		    off
-  }
-  AnnotationDefaults {
-    HorizontalAlignment	    "center"
-    VerticalAlignment	    "middle"
-    ForegroundColor	    "black"
-    BackgroundColor	    "white"
-    DropShadow		    off
-    FontName		    "Helvetica"
-    FontSize		    10
-    FontWeight		    "normal"
-    FontAngle		    "normal"
-    UseDisplayTextAsClickCallback off
-  }
-  LineDefaults {
-    FontName		    "Helvetica"
-    FontSize		    9
-    FontWeight		    "normal"
-    FontAngle		    "normal"
-  }
-  MaskDefaults {
-    SelfModifiable	    "off"
-    IconFrame		    "on"
-    IconOpaque		    "on"
-    RunInitForIconRedraw    "off"
-    IconRotate		    "none"
-    PortRotate		    "default"
-    IconUnits		    "autoscale"
-  }
-  MaskParameterDefaults {
-    Evaluate		    "on"
-    Tunable		    "on"
-    NeverSave		    "off"
-    Internal		    "off"
-    ReadOnly		    "off"
-    Enabled		    "on"
-    Visible		    "on"
-    ToolTip		    "on"
-  }
-  BlockParameterDefaults {
-    Block {
-      BlockType		      BusCreator
-      DisplayOption	      "none"
-      OutDataTypeStr	      "Inherit: auto"
-      NonVirtualBus	      off
-    }
-    Block {
-      BlockType		      BusSelector
-      OutputSignals	      "signal1,signal2,signal3"
-      OutputAsBus	      off
-    }
-    Block {
-      BlockType		      Constant
-      Value		      "1"
-      VectorParams1D	      on
-      SamplingMode	      "Sample based"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Inherit from 'Constant value'"
-      LockScale		      off
-      SampleTime	      "inf"
-      FramePeriod	      "inf"
-      PreserveConstantTs      off
-    }
-    Block {
-      BlockType		      Delay
-      DelayLengthSource	      "Dialog"
-      DelayLength	      "2"
-      DelayLengthUpperLimit   "100"
-      InitialConditionSource  "Dialog"
-      InitialCondition	      "0.0"
-      ExternalReset	      "None"
-      ShowEnablePort	      off
-      PreventDirectFeedthrough off
-      DiagnosticForOutOfRangeDelayLength "None"
-      RemoveProtectionDelayLength off
-      InputProcessing	      "Elements as channels (sample based)"
-      UseCircularBuffer	      off
-      SampleTime	      "-1"
-      StateMustResolveToSignalObject off
-      CodeGenStateStorageClass "Auto"
-    }
-    Block {
-      BlockType		      Demux
-      Outputs		      "4"
-      DisplayOption	      "none"
-      BusSelectionMode	      off
-    }
-    Block {
-      BlockType		      DiscreteFilter
-      NumeratorSource	      "Dialog"
-      Numerator		      "[1]"
-      DenominatorSource	      "Dialog"
-      Denominator	      "[1 0.5]"
-      InitialStatesSource     "Dialog"
-      InitialStates	      "0"
-      InputProcessing	      "Elements as channels (sample based)"
-      ExternalReset	      "None"
-      InitialDenominatorStates "0"
-      FilterStructure	      "Direct form II"
-      SampleTime	      "-1"
-      a0EqualsOne	      off
-      NumCoefMin	      "[]"
-      NumCoefMax	      "[]"
-      DenCoefMin	      "[]"
-      DenCoefMax	      "[]"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      StateDataTypeStr	      "Inherit: Same as input"
-      MultiplicandDataTypeStr "Inherit: Same as input"
-      NumCoefDataTypeStr      "Inherit: Inherit via internal rule"
-      DenCoefDataTypeStr      "Inherit: Inherit via internal rule"
-      NumProductDataTypeStr   "Inherit: Inherit via internal rule"
-      DenProductDataTypeStr   "Inherit: Inherit via internal rule"
-      NumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-      DenAccumDataTypeStr     "Inherit: Inherit via internal rule"
-      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	off
-      StateMustResolveToSignalObject off
-      RTWStateStorageClass    "Auto"
-    }
-    Block {
-      BlockType		      DiscreteIntegrator
-      IntegratorMethod	      "Integration: Forward Euler"
-      gainval		      "1.0"
-      ExternalReset	      "none"
-      InitialConditionSource  "internal"
-      InitialCondition	      "0"
-      InitialConditionSetting "Output"
-      SampleTime	      "1"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	off
-      LimitOutput	      off
-      UpperSaturationLimit    "inf"
-      LowerSaturationLimit    "-inf"
-      ShowSaturationPort      off
-      ShowStatePort	      off
-      IgnoreLimit	      off
-      StateMustResolveToSignalObject off
-      RTWStateStorageClass    "Auto"
-    }
-    Block {
-      BlockType		      FromWorkspace
-      VariableName	      "simulink_input"
-      OutDataTypeStr	      "Inherit: auto"
-      SampleTime	      "-1"
-      Interpolate	      on
-      ZeroCross		      off
-      OutputAfterFinalValue   "Extrapolation"
-    }
-    Block {
-      BlockType		      Gain
-      Gain		      "1"
-      Multiplication	      "Element-wise(K.*u)"
-      ParamMin		      "[]"
-      ParamMax		      "[]"
-      ParamDataTypeStr	      "Inherit: Same as input"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Same as input"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	on
-      SampleTime	      "-1"
-    }
-    Block {
-      BlockType		      Ground
-    }
-    Block {
-      BlockType		      Inport
-      Port		      "1"
-      OutputFunctionCall      off
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: auto"
-      LockScale		      off
-      BusOutputAsStruct	      off
-      PortDimensions	      "-1"
-      VarSizeSig	      "Inherit"
-      SampleTime	      "-1"
-      SignalType	      "auto"
-      SamplingMode	      "auto"
-      LatchByDelayingOutsideSignal off
-      LatchInputForFeedbackSignals off
-      Interpolate	      on
-    }
-    Block {
-      BlockType		      Integrator
-      ExternalReset	      "none"
-      InitialConditionSource  "internal"
-      InitialCondition	      "0"
-      LimitOutput	      off
-      UpperSaturationLimit    "inf"
-      LowerSaturationLimit    "-inf"
-      WrapState		      off
-      WrappedStateUpperValue  "pi"
-      WrappedStateLowerValue  "-pi"
-      ShowSaturationPort      off
-      ShowStatePort	      off
-      AbsoluteTolerance	      "auto"
-      IgnoreLimit	      off
-      ZeroCross		      on
-      ContinuousStateAttributes	"''"
-    }
-    Block {
-      BlockType		      Mux
-      Inputs		      "4"
-      DisplayOption	      "none"
-      UseBusObject	      off
-      BusObject		      "BusObject"
-      NonVirtualBus	      off
-    }
-    Block {
-      BlockType		      Outport
-      Port		      "1"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: auto"
-      LockScale		      off
-      BusOutputAsStruct	      off
-      PortDimensions	      "-1"
-      VarSizeSig	      "Inherit"
-      SampleTime	      "-1"
-      SignalType	      "auto"
-      SamplingMode	      "auto"
-      SourceOfInitialOutputValue "Dialog"
-      OutputWhenDisabled      "held"
-      InitialOutput	      "[]"
-    }
-    Block {
-      BlockType		      Quantizer
-      QuantizationInterval    "0.5"
-      LinearizeAsGain	      on
-      SampleTime	      "-1"
-    }
-    Block {
-      BlockType		      RandomNumber
-      Mean		      "0"
-      Variance		      "1"
-      Seed		      "0"
-      SampleTime	      "-1"
-      VectorParams1D	      on
-    }
-    Block {
-      BlockType		      RateTransition
-      Integrity		      on
-      Deterministic	      on
-      X0		      "0"
-      OutPortSampleTimeOpt    "Specify"
-      OutPortSampleTimeMultiple	"1"
-      OutPortSampleTime	      "-1"
-    }
-    Block {
-      BlockType		      S-Function
-      FunctionName	      "system"
-      SFunctionModules	      "''"
-      PortCounts	      "[]"
-    }
-    Block {
-      BlockType		      Saturate
-      UpperLimitSource	      "Dialog"
-      UpperLimit	      "0.5"
-      LowerLimitSource	      "Dialog"
-      LowerLimit	      "-0.5"
-      LinearizeAsGain	      on
-      ZeroCross		      on
-      SampleTime	      "-1"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Same as input"
-      LockScale		      off
-      RndMeth		      "Floor"
-    }
-    Block {
-      BlockType		      Scope
-      Floating		      off
-    }
-    Block {
-      BlockType		      Step
-      Time		      "1"
-      Before		      "0"
-      After		      "1"
-      SampleTime	      "-1"
-      VectorParams1D	      on
-      ZeroCross		      on
-    }
-    Block {
-      BlockType		      SubSystem
-      ShowPortLabels	      "FromPortIcon"
-      Permissions	      "ReadWrite"
-      PermitHierarchicalResolution "All"
-      TreatAsAtomicUnit	      off
-      MinAlgLoopOccurrences   off
-      PropExecContextOutsideSubsystem off
-      SystemSampleTime	      "-1"
-      RTWSystemCode	      "Auto"
-      RTWFcnNameOpts	      "Auto"
-      RTWFileNameOpts	      "Auto"
-      FunctionInterfaceSpec   "void_void"
-      FunctionWithSeparateData off
-      RTWMemSecFuncInitTerm   "Inherit from model"
-      RTWMemSecFuncExecute    "Inherit from model"
-      RTWMemSecDataConstants  "Inherit from model"
-      RTWMemSecDataInternal   "Inherit from model"
-      RTWMemSecDataParameters "Inherit from model"
-      SimViewingDevice	      off
-      DataTypeOverride	      "UseLocalSettings"
-      DataTypeOverrideAppliesTo	"AllNumericTypes"
-      MinMaxOverflowLogging   "UseLocalSettings"
-      Opaque		      off
-      MaskHideContents	      off
-      SFBlockType	      "NONE"
-      GeneratePreprocessorConditionals off
-      PropagateVariantConditions off
-      TreatAsGroupedWhenPropagatingVariantConditions on
-      ContentPreviewEnabled   off
-      IsWebBlock	      off
-    }
-    Block {
-      BlockType		      Sum
-      IconShape		      "rectangular"
-      Inputs		      "++"
-      CollapseMode	      "All dimensions"
-      CollapseDim	      "1"
-      InputSameDT	      on
-      AccumDataTypeStr	      "Inherit: Inherit via internal rule"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Same as first input"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	on
-      SampleTime	      "-1"
-    }
-    Block {
-      BlockType		      Terminator
-    }
-    Block {
-      BlockType		      ToWorkspace
-      VariableName	      "simulink_output"
-      MaxDataPoints	      "1000"
-      Decimation	      "1"
-      SaveFormat	      "Array"
-      Save2DSignal	      "Inherit from input (this choice will be removed - see release notes)"
-      FixptAsFi		      off
-      NumInputs		      "1"
-      SampleTime	      "0"
-    }
-    Block {
-      BlockType		      TransportDelay
-      DelayTime		      "1"
-      InitialOutput	      "0"
-      BufferSize	      "1024"
-      FixedBuffer	      off
-      TransDelayFeedthrough   off
-      PadeOrder		      "0"
-    }
-    Block {
-      BlockType		      ZeroOrderHold
-      SampleTime	      "1"
-    }
-  }
-  System {
-    Name		    "Quadcopter_Model_R2015_A"
-    Location		    [-8, -8, 1928, 1048]
-    Open		    off
-    ModelBrowserVisibility  off
-    ModelBrowserWidth	    200
-    ScreenColor		    "white"
-    PaperOrientation	    "landscape"
-    PaperPositionMode	    "auto"
-    PaperType		    "usletter"
-    PaperUnits		    "inches"
-    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-    TiledPageScale	    1
-    ShowPageBoundaries	    off
-    ZoomFactor		    "100"
-    ReportName		    "simulink-default.rpt"
-    SIDHighWatermark	    "1424"
-    Block {
-      BlockType		      SubSystem
-      Name		      "     Sensors   "
-      SID		      "650"
-      Ports		      [6, 3]
-      Position		      [1300, 422, 1520, 658]
-      ZOrder		      73
-      ShowName		      off
-      RequestExecContextInheritance off
-      Variant		      off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		24
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('input', 1, '^{B}Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on');"
-	"\nport_label('input', 3, '^{B}v_o', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmode', 'on');\nport_labe"
-	"l('input', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('input', 6, '^{B}g', 'texmode', 'on');\nport_label('output"
-	"', 1, '\\Theta_{filtered}', 'texmode', 'on');\nport_label('output', 2, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_"
-	"label('output', 3, '^{E}r_o', 'texmode', 'on');\ndisp('Sensors', 'texmode', 'on'); "
-      }
-      System {
-	Name			"     Sensors   "
-	Location		[-8, -8, 1928, 1048]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"50"
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_Omega"
-	  SID			  "651"
-	  Position		  [635, 568, 665, 582]
-	  ZOrder		  265
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "euler_angles"
-	  SID			  "652"
-	  Position		  [830, 1338, 860, 1352]
-	  ZOrder		  266
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_vo"
-	  SID			  "653"
-	  Position		  [635, 503, 665, 517]
-	  ZOrder		  267
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "E_ro"
-	  SID			  "654"
-	  Position		  [985, 1313, 1015, 1327]
-	  ZOrder		  268
-	  Port			  "4"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_vo_dot"
-	  SID			  "655"
-	  Position		  [635, 438, 665, 452]
-	  ZOrder		  269
-	  Port			  "5"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_g"
-	  SID			  "656"
-	  Position		  [635, 633, 665, 647]
-	  ZOrder		  273
-	  Port			  "6"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "3D Graphical Simulation"
-	  SID			  "698"
-	  Ports			  [2]
-	  Position		  [1265, 1425, 1415, 1485]
-	  ZOrder		  287
-	  Commented		  "on"
-	  RequestExecContextInheritance	off
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    25
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input',1,'r_{o}','texmode','on')\nport_label('input',2,'\\Theta','texmode','on')"
-	  }
-	  System {
-	    Name		    "3D Graphical Simulation"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Displacement"
-	      SID		      "699"
-	      Position		      [110, 218, 140, 232]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Euler Angles"
-	      SID		      "700"
-	      Position		      [125, 108, 155, 122]
-	      ZOrder		      -2
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator"
-	      SID		      "701"
-	      Ports		      [3, 1]
-	      Position		      [600, 76, 610, 154]
-	      ZOrder		      -3
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	      InheritFromInputs	      on
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator1"
-	      SID		      "702"
-	      Ports		      [3, 1]
-	      Position		      [630, 191, 640, 269]
-	      ZOrder		      -4
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	      InheritFromInputs	      on
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator2"
-	      SID		      "703"
-	      Ports		      [3, 1]
-	      Position		      [385, 75, 390, 155]
-	      ZOrder		      -5
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	      InheritFromInputs	      on
-	    }
-	    Block {
-	      BlockType		      BusSelector
-	      Name		      "Bus\nSelector"
-	      SID		      "704"
-	      Ports		      [1, 3]
-	      Position		      [500, 77, 505, 153]
-	      ZOrder		      -6
-	      ShowName		      off
-	      OutputSignals	      "phi,theta,psi"
-	      Port {
-		PortNumber		1
-		Name			"<phi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"<theta>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"<psi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux"
-	      SID		      "705"
-	      Ports		      [1, 3]
-	      Position		      [440, 183, 450, 267]
-	      ZOrder		      -7
-	      BackgroundColor	      "black"
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux1"
-	      SID		      "706"
-	      Ports		      [1, 3]
-	      Position		      [290, 75, 295, 155]
-	      ZOrder		      -8
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	      Port {
-		PortNumber		1
-		Name			"phi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"theta"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"psi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain"
-	      SID		      "707"
-	      Position		      [550, 240, 580, 270]
-	      ZOrder		      -10
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain1"
-	      SID		      "708"
-	      Position		      [670, 208, 710, 252]
-	      ZOrder		      -11
-	      Gain		      "eye(3)*1"
-	      Multiplication	      "Matrix(K*u)"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain2"
-	      SID		      "709"
-	      Position		      [550, 190, 580, 220]
-	      ZOrder		      -12
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "MATLAB Function"
-	      SID		      "710"
-	      Ports		      [1, 1]
-	      Position		      [655, 92, 725, 138]
-	      ZOrder		      5
-	      ErrorFcn		      "Stateflow.Translate.translate"
-	      PermitHierarchicalResolution "ParametersOnly"
-	      TreatAsAtomicUnit	      on
-	      RequestExecContextInheritance off
-	      SFBlockType	      "MATLAB Function"
-	      Variant		      off
-	      System {
-		Name			"MATLAB Function"
-		Location		[223, 338, 826, 833]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		SIDHighWatermark	"21"
-		Block {
-		  BlockType		  Inport
-		  Name			  "u"
-		  SID			  "710::1"
-		  Position		  [20, 101, 40, 119]
-		  ZOrder		  -1
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Demux
-		  Name			  " Demux "
-		  SID			  "710::20"
-		  Ports			  [1, 1]
-		  Position		  [270, 230, 320, 270]
-		  ZOrder		  11
-		  Outputs		  "1"
-		}
-		Block {
-		  BlockType		  S-Function
-		  Name			  " SFunction "
-		  SID			  "710::19"
-		  Tag			  "Stateflow S-Function Quadcopter_Model_R2015_A 11"
-		  Ports			  [1, 2]
-		  Position		  [180, 100, 230, 160]
-		  ZOrder		  10
-		  FunctionName		  "sf_sfun"
-		  PortCounts		  "[1 2]"
-		  SFunctionDeploymentMode off
-		  EnableBusSupport	  on
-		  Port {
-		    PortNumber		    2
-		    Name		    "y"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		}
-		Block {
-		  BlockType		  Terminator
-		  Name			  " Terminator "
-		  SID			  "710::21"
-		  Position		  [460, 241, 480, 259]
-		  ZOrder		  12
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "y"
-		  SID			  "710::5"
-		  Position		  [460, 101, 480, 119]
-		  ZOrder		  -5
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "u"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  1
-		}
-		Line {
-		  Name			  "y"
-		  ZOrder		  2
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  2
-		  DstBlock		  "y"
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  3
-		  SrcBlock		  " Demux "
-		  SrcPort		  1
-		  DstBlock		  " Terminator "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  4
-		  SrcBlock		  " SFunction "
-		  SrcPort		  1
-		  DstBlock		  " Demux "
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition"
-	      SID		      "711"
-	      Position		      [755, 94, 795, 136]
-	      ZOrder		      -13
-	      NamePlacement	      "alternate"
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition1"
-	      SID		      "712"
-	      Position		      [735, 210, 770, 250]
-	      ZOrder		      -14
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "VR Sink"
-	      SID		      "713"
-	      Ports		      [2]
-	      Position		      [865, 76, 1055, 234]
-	      ZOrder		      -15
-	      LibraryVersion	      "1.36"
-	      SourceBlock	      "vrlib/VR Sink"
-	      SourceType	      "Virtual Reality Sink"
-	      InstantiateOnLoad	      on
-	      SampleTime	      "-1"
-	      ViewEnable	      on
-	      RemoteChange	      off
-	      RemoteView	      off
-	      FieldsWritten	      "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double"
-	      WorldFileName	      "quadrotor_world_ucart.wrl"
-	      AutoView		      on
-	      VideoDimensions	      "[]"
-	      AllowVariableSize	      off
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "Displacement"
-	      SrcPort		      1
-	      DstBlock		      "Demux"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "Bus\nCreator2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nSelector"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "Demux"
-	      SrcPort		      1
-	      Points		      [40, 0; 0, 40; 120, 0]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "Gain"
-	      SrcPort		      1
-	      Points		      [5, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "Gain2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Rate Transition1"
-	      SrcPort		      1
-	      Points		      [35, 0; 0, -35]
-	      DstBlock		      "VR Sink"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      7
-	      SrcBlock		      "Rate Transition"
-	      SrcPort		      1
-	      DstBlock		      "VR Sink"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "Demux"
-	      SrcPort		      3
-	      DstBlock		      "Gain"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "Demux"
-	      SrcPort		      2
-	      Points		      [80, 0]
-	      DstBlock		      "Gain2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      10
-	      SrcBlock		      "Bus\nCreator1"
-	      SrcPort		      1
-	      DstBlock		      "Gain1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "<phi>"
-	      ZOrder		      11
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      1
-	      Points		      [0, -10; 45, 0; 0, 60]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "<psi>"
-	      ZOrder		      12
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      3
-	      Points		      [0, -10; 75, 0]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "<theta>"
-	      ZOrder		      13
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      2
-	      Points		      [30, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      14
-	      SrcBlock		      "Gain1"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "psi"
-	      ZOrder		      15
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      3
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "theta"
-	      ZOrder		      16
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      2
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "phi"
-	      ZOrder		      17
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "Euler Angles"
-	      SrcPort		      1
-	      DstBlock		      "Demux1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "Bus\nCreator"
-	      SrcPort		      1
-	      DstBlock		      "MATLAB Function"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      20
-	      SrcBlock		      "MATLAB Function"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "3D Graphical Simulation1"
-	  SID			  "714"
-	  Ports			  [2]
-	  Position		  [1900, 1435, 2050, 1495]
-	  ZOrder		  290
-	  Commented		  "on"
-	  RequestExecContextInheritance	off
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    26
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input',1, '\\Theta','texmode','on')\nport_label('input',2,'r_{o}','texmode','on')"
-	  }
-	  System {
-	    Name		    "3D Graphical Simulation1"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Euler Angles\n"
-	      SID		      "715"
-	      Position		      [180, 108, 210, 122]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Displacement"
-	      SID		      "716"
-	      Position		      [180, 218, 210, 232]
-	      ZOrder		      -2
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator"
-	      SID		      "717"
-	      Ports		      [3, 1]
-	      Position		      [600, 76, 610, 154]
-	      ZOrder		      -3
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	      InheritFromInputs	      on
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator1"
-	      SID		      "718"
-	      Ports		      [3, 1]
-	      Position		      [630, 191, 640, 269]
-	      ZOrder		      -4
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	      InheritFromInputs	      on
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator2"
-	      SID		      "719"
-	      Ports		      [3, 1]
-	      Position		      [385, 75, 390, 155]
-	      ZOrder		      -5
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	      InheritFromInputs	      on
-	    }
-	    Block {
-	      BlockType		      BusSelector
-	      Name		      "Bus\nSelector"
-	      SID		      "720"
-	      Ports		      [1, 3]
-	      Position		      [500, 77, 505, 153]
-	      ZOrder		      -6
-	      ShowName		      off
-	      OutputSignals	      "phi,theta,psi"
-	      Port {
-		PortNumber		1
-		Name			"<phi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"<theta>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"<psi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux"
-	      SID		      "721"
-	      Ports		      [1, 3]
-	      Position		      [440, 183, 450, 267]
-	      ZOrder		      -7
-	      BackgroundColor	      "black"
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux1"
-	      SID		      "722"
-	      Ports		      [1, 3]
-	      Position		      [290, 75, 295, 155]
-	      ZOrder		      -8
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	      Port {
-		PortNumber		1
-		Name			"phi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"theta"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"psi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain"
-	      SID		      "723"
-	      Position		      [550, 240, 580, 270]
-	      ZOrder		      -10
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain1"
-	      SID		      "724"
-	      Position		      [670, 208, 710, 252]
-	      ZOrder		      -11
-	      Gain		      "eye(3)*1"
-	      Multiplication	      "Matrix(K*u)"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain2"
-	      SID		      "725"
-	      Position		      [550, 190, 580, 220]
-	      ZOrder		      -12
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "MATLAB Function"
-	      SID		      "726"
-	      Ports		      [1, 1]
-	      Position		      [655, 92, 725, 138]
-	      ZOrder		      5
-	      ErrorFcn		      "Stateflow.Translate.translate"
-	      PermitHierarchicalResolution "ParametersOnly"
-	      TreatAsAtomicUnit	      on
-	      RequestExecContextInheritance off
-	      SFBlockType	      "MATLAB Function"
-	      Variant		      off
-	      System {
-		Name			"MATLAB Function"
-		Location		[223, 338, 826, 833]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		SIDHighWatermark	"21"
-		Block {
-		  BlockType		  Inport
-		  Name			  "u"
-		  SID			  "726::1"
-		  Position		  [20, 101, 40, 119]
-		  ZOrder		  -1
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Demux
-		  Name			  " Demux "
-		  SID			  "726::20"
-		  Ports			  [1, 1]
-		  Position		  [270, 230, 320, 270]
-		  ZOrder		  11
-		  Outputs		  "1"
-		}
-		Block {
-		  BlockType		  S-Function
-		  Name			  " SFunction "
-		  SID			  "726::19"
-		  Tag			  "Stateflow S-Function Quadcopter_Model_R2015_A 3"
-		  Ports			  [1, 2]
-		  Position		  [180, 100, 230, 160]
-		  ZOrder		  10
-		  FunctionName		  "sf_sfun"
-		  PortCounts		  "[1 2]"
-		  SFunctionDeploymentMode off
-		  EnableBusSupport	  on
-		  Port {
-		    PortNumber		    2
-		    Name		    "y"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		}
-		Block {
-		  BlockType		  Terminator
-		  Name			  " Terminator "
-		  SID			  "726::21"
-		  Position		  [460, 241, 480, 259]
-		  ZOrder		  12
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "y"
-		  SID			  "726::5"
-		  Position		  [460, 101, 480, 119]
-		  ZOrder		  -5
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "u"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  1
-		}
-		Line {
-		  Name			  "y"
-		  ZOrder		  2
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  2
-		  DstBlock		  "y"
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  3
-		  SrcBlock		  " Demux "
-		  SrcPort		  1
-		  DstBlock		  " Terminator "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  4
-		  SrcBlock		  " SFunction "
-		  SrcPort		  1
-		  DstBlock		  " Demux "
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition"
-	      SID		      "727"
-	      Position		      [755, 94, 795, 136]
-	      ZOrder		      -13
-	      NamePlacement	      "alternate"
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition1"
-	      SID		      "728"
-	      Position		      [745, 210, 780, 250]
-	      ZOrder		      -14
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "VR Sink"
-	      SID		      "729"
-	      Ports		      [2]
-	      Position		      [865, 76, 1055, 234]
-	      ZOrder		      -15
-	      LibraryVersion	      "1.36"
-	      SourceBlock	      "vrlib/VR Sink"
-	      SourceType	      "Virtual Reality Sink"
-	      InstantiateOnLoad	      on
-	      SampleTime	      "-1"
-	      ViewEnable	      on
-	      RemoteChange	      off
-	      RemoteView	      off
-	      FieldsWritten	      "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double"
-	      WorldFileName	      "quadrotor_world_ucart.wrl"
-	      AutoView		      on
-	      VideoDimensions	      "[]"
-	      AllowVariableSize	      off
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "Bus\nCreator2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nSelector"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "Demux"
-	      SrcPort		      1
-	      Points		      [40, 0; 0, 40; 120, 0]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "Gain"
-	      SrcPort		      1
-	      Points		      [5, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "Gain2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "Rate Transition1"
-	      SrcPort		      1
-	      Points		      [25, 0; 0, -35]
-	      DstBlock		      "VR Sink"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Rate Transition"
-	      SrcPort		      1
-	      DstBlock		      "VR Sink"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      7
-	      SrcBlock		      "Demux"
-	      SrcPort		      3
-	      DstBlock		      "Gain"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "Demux"
-	      SrcPort		      2
-	      Points		      [80, 0]
-	      DstBlock		      "Gain2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "Bus\nCreator1"
-	      SrcPort		      1
-	      DstBlock		      "Gain1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "<phi>"
-	      ZOrder		      10
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      1
-	      Points		      [0, -10; 45, 0; 0, 60]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "<psi>"
-	      ZOrder		      11
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      3
-	      Points		      [0, -10; 75, 0]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "<theta>"
-	      ZOrder		      12
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      2
-	      Points		      [30, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      13
-	      SrcBlock		      "Gain1"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "psi"
-	      ZOrder		      14
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      3
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "theta"
-	      ZOrder		      15
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      2
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "phi"
-	      ZOrder		      16
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      17
-	      SrcBlock		      "Bus\nCreator"
-	      SrcPort		      1
-	      DstBlock		      "MATLAB Function"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "MATLAB Function"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "Displacement"
-	      SrcPort		      1
-	      DstBlock		      "Demux"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      20
-	      SrcBlock		      "Euler Angles\n"
-	      SrcPort		      1
-	      DstBlock		      "Demux1"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Aeb\n\n\n\n\n\n\n\n\n\n"
-	  SID			  "679"
-	  Ports			  [2, 1]
-	  Position		  [1475, 579, 1655, 701]
-	  ZOrder		  275
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    27
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU"
-	    "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode',"
-	    " 'on');"
-	  }
-	  System {
-	    Name		    "Aeb\n\n\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "25"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "gyro_reading"
-	      SID		      "679::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles_filtered"
-	      SID		      "679::22"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "679::24"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      15
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "679::23"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 12"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      14
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_rates_IMU"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "679::25"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      16
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_rates_IMU"
-	      SID		      "679::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "gyro_reading"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles_filtered"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "euler_rates_IMU"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_rates_IMU"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Aeb_c\n\n\n\n\n\n\n\n\n\n1"
-	  SID			  "1335"
-	  Ports			  [2, 1]
-	  Position		  [1460, 969, 1640, 1091]
-	  ZOrder		  322
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    28
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU"
-	    "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode',"
-	    " 'on');"
-	  }
-	  System {
-	    Name		    "Aeb_c\n\n\n\n\n\n\n\n\n\n1"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "25"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "gyro_reading"
-	      SID		      "1335::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles_filtered"
-	      SID		      "1335::22"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "1335::24"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      15
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "1335::23"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 16"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      14
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_rates_IMU"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "1335::25"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      16
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_rates_IMU"
-	      SID		      "1335::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "gyro_reading"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles_filtered"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "euler_rates_IMU"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_rates_IMU"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Calculate Pitch and Roll"
-	  SID			  "680"
-	  Ports			  [2, 2]
-	  Position		  [1485, 379, 1655, 521]
-	  ZOrder		  284
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    29
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Accelerometer Reading', 'texmode', 'on');\nport_label('input', 2, '\\phi_{a"
-	    "ccel}', 'texmode', 'on');\nport_label('output', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('output', 2, "
-	    "'\\phi_{accel}', 'texmode', 'on');\ndisp('Calculate Pitch and Roll', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Calculate Pitch and Roll"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "26"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_reading"
-	      SID		      "680::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_roll_prev"
-	      SID		      "680::23"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      14
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "680::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "680::19"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 13"
-	      Ports		      [2, 3]
-	      Position		      [180, 105, 230, 185]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 3]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"accel_pitch"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"accel_roll"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "680::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accel_pitch"
-	      SID		      "680::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accel_roll"
-	      SID		      "680::22"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "accel_reading"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "accel_roll_prev"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "accel_pitch"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "accel_pitch"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "accel_roll"
-	      ZOrder		      4
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "accel_roll"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Complimentary Filter"
-	  SID			  "1339"
-	  Ports			  [4, 1]
-	  Position		  [1880, 372, 2065, 713]
-	  ZOrder		  326
-	  ForegroundColor	  "red"
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    30
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('input', 2, '\\phi_{accel}'"
-	    ", 'texmode', 'on');\nport_label('input', 3, '\\Theta_{Gyro}', 'texmode', 'on');\n%port_label('input', 4, '\\Theta"
-	    "_{IMU}', 'texmode', 'on');\nport_label('output', 1, '\\Theta_{IMU}', 'texmode', 'on');\ndisp('Complementary Filte"
-	    "r', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Complimentary Filter"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "35"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_pitch"
-	      SID		      "1339::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_roll"
-	      SID		      "1339::29"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      20
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_rates_gyro"
-	      SID		      "1339::22"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      13
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "prev_euler_angles"
-	      SID		      "1339::35"
-	      Position		      [20, 206, 40, 224]
-	      ZOrder		      21
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "1339::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "1339::19"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 19"
-	      Ports		      [4, 2]
-	      Position		      [180, 147, 230, 248]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[4 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_angles_IMU"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "1339::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_angles_IMU"
-	      SID		      "1339::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      7
-	      SrcBlock		      "accel_pitch"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "accel_roll"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "euler_rates_gyro"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      10
-	      SrcBlock		      "prev_euler_angles"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      4
-	    }
-	    Line {
-	      Name		      "euler_angles_IMU"
-	      ZOrder		      11
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_angles_IMU"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      12
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      13
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Delay
-	  Name			  "Delay"
-	  SID			  "1341"
-	  Ports			  [1, 1]
-	  Position		  [1955, 728, 1990, 762]
-	  ZOrder		  328
-	  BlockMirror		  on
-	  InputPortMap		  "u0"
-	  DelayLength		  "1"
-	  InitialCondition	  "0"
-	}
-	Block {
-	  BlockType		  Delay
-	  Name			  "Delay1"
-	  SID			  "731"
-	  Ports			  [1, 1]
-	  Position		  [1555, 528, 1590, 562]
-	  ZOrder		  285
-	  BlockMirror		  on
-	  ForegroundColor	  "red"
-	  InputPortMap		  "u0"
-	  DelayLength		  "1"
-	  InitialCondition	  "0"
-	  SampleTime		  "Tq"
-	}
-	Block {
-	  BlockType		  Delay
-	  Name			  "Delay2"
-	  SID			  "772"
-	  Ports			  [1, 1]
-	  Position		  [695, 428, 730, 462]
-	  ZOrder		  304
-	  InputPortMap		  "u0"
-	  DelayLength		  "1"
-	  InitialCondition	  "0"
-	  SampleTime		  "Tq"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux"
-	  SID			  "1344"
-	  Ports			  [1, 3]
-	  Position		  [920, 1313, 925, 1377]
-	  ZOrder		  329
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux1"
-	  SID			  "1404"
-	  Ports			  [1, 2]
-	  Position		  [2285, 726, 2290, 764]
-	  ZOrder		  347
-	  ShowName		  off
-	  Outputs		  "2"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux2"
-	  SID			  "1405"
-	  Ports			  [1, 2]
-	  Position		  [2285, 916, 2290, 954]
-	  ZOrder		  348
-	  ShowName		  off
-	  Outputs		  "2"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Reference
-	  Name			  "First-Order\nHold"
-	  SID			  "734"
-	  Ports			  [1, 1]
-	  Position		  [1790, 1435, 1825, 1465]
-	  ZOrder		  292
-	  ForegroundColor	  "yellow"
-	  LibraryVersion	  "1.388"
-	  DisableCoverage	  on
-	  SourceBlock		  "simulink/Discrete/First-Order\nHold"
-	  SourceType		  "First-Order Hold"
-	  ContentPreviewEnabled	  off
-	  Ts			  "5e-3"
-	}
-	Block {
-	  BlockType		  Reference
-	  Name			  "First-Order\nHold1"
-	  SID			  "735"
-	  Ports			  [1, 1]
-	  Position		  [1790, 1530, 1825, 1560]
-	  ZOrder		  296
-	  ForegroundColor	  "yellow"
-	  LibraryVersion	  "1.388"
-	  DisableCoverage	  on
-	  SourceBlock		  "simulink/Discrete/First-Order\nHold"
-	  SourceType		  "First-Order Hold"
-	  ContentPreviewEnabled	  off
-	  Ts			  "5e-3"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "IMU\n\n\n\n\n\n"
-	  SID			  "658"
-	  Ports			  [4, 2]
-	  Position		  [765, 410, 960, 675]
-	  ZOrder		  272
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    31
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode'"
-	    ", 'on')\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')"
-	    "\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_label('output', 2, 'Gyroscope Reading',"
-	    " 'texmode', 'on')\ndisp('IMU', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "IMU\n\n\n\n\n\n"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo_dot"
-	      SID		      "659"
-	      Position		      [110, 173, 140, 187]
-	      ZOrder		      17
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo"
-	      SID		      "660"
-	      Position		      [110, 208, 140, 222]
-	      ZOrder		      25
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_Omega"
-	      SID		      "661"
-	      Position		      [110, 243, 140, 257]
-	      ZOrder		      26
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_g"
-	      SID		      "662"
-	      Position		      [110, 278, 140, 292]
-	      ZOrder		      27
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "\n\n\n\n\n\n\n"
-	      SID		      "663"
-	      Ports		      [5, 2]
-	      Position		      [250, 165, 445, 335]
-	      ZOrder		      1
-	      LibraryVersion	      "1.32"
-	      ErrorFcn		      "Stateflow.Translate.translate"
-	      PermitHierarchicalResolution "ParametersOnly"
-	      TreatAsAtomicUnit	      on
-	      RequestExecContextInheritance off
-	      SFBlockType	      "MATLAB Function"
-	      Variant		      off
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		32
-		$ClassName		"Simulink.Mask"
-		Display			"port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode', 'on'"
-		")\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')\nport_la"
-		"bel('input', 5, 'r_{oc}', 'texmode', 'on')\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_"
-		"label('output', 2, 'Gyroscope Reading', 'texmode', 'on')\ndisp('Ideal IMU', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"\n\n\n\n\n\n\n"
-		Location		[223, 338, 826, 833]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		SIDHighWatermark	"31"
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_vo_dot"
-		  SID			  "663::1"
-		  Position		  [20, 101, 40, 119]
-		  ZOrder		  -1
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_vo"
-		  SID			  "663::22"
-		  Position		  [20, 136, 40, 154]
-		  ZOrder		  13
-		  Port			  "2"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_Omega"
-		  SID			  "663::19"
-		  Position		  [20, 171, 40, 189]
-		  ZOrder		  10
-		  Port			  "3"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_g"
-		  SID			  "663::20"
-		  Position		  [20, 206, 40, 224]
-		  ZOrder		  11
-		  Port			  "4"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "r_oc"
-		  SID			  "663::23"
-		  Position		  [20, 246, 40, 264]
-		  ZOrder		  14
-		  Port			  "5"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Demux
-		  Name			  " Demux "
-		  SID			  "663::25"
-		  Ports			  [1, 1]
-		  Position		  [270, 230, 320, 270]
-		  ZOrder		  16
-		  Outputs		  "1"
-		}
-		Block {
-		  BlockType		  S-Function
-		  Name			  " SFunction "
-		  SID			  "663::24"
-		  Tag			  "Stateflow S-Function Quadcopter_Model_R2015_A 10"
-		  Ports			  [5, 3]
-		  Position		  [180, 110, 230, 230]
-		  ZOrder		  15
-		  FunctionName		  "sf_sfun"
-		  Parameters		  "g"
-		  PortCounts		  "[5 3]"
-		  SFunctionDeploymentMode off
-		  EnableBusSupport	  on
-		  Port {
-		    PortNumber		    2
-		    Name		    "accelReading"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		  Port {
-		    PortNumber		    3
-		    Name		    "gyroReading"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		}
-		Block {
-		  BlockType		  Terminator
-		  Name			  " Terminator "
-		  SID			  "663::26"
-		  Position		  [460, 241, 480, 259]
-		  ZOrder		  17
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "accelReading"
-		  SID			  "663::5"
-		  Position		  [460, 101, 480, 119]
-		  ZOrder		  -5
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "gyroReading"
-		  SID			  "663::21"
-		  Position		  [460, 136, 480, 154]
-		  ZOrder		  12
-		  Port			  "2"
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "B_vo_dot"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  2
-		  SrcBlock		  "B_vo"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  2
-		}
-		Line {
-		  ZOrder		  3
-		  SrcBlock		  "B_Omega"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  3
-		}
-		Line {
-		  ZOrder		  4
-		  SrcBlock		  "B_g"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  4
-		}
-		Line {
-		  ZOrder		  5
-		  SrcBlock		  "r_oc"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  5
-		}
-		Line {
-		  Name			  "accelReading"
-		  ZOrder		  6
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  2
-		  DstBlock		  "accelReading"
-		  DstPort		  1
-		}
-		Line {
-		  Name			  "gyroReading"
-		  ZOrder		  7
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  3
-		  DstBlock		  "gyroReading"
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  8
-		  SrcBlock		  " Demux "
-		  SrcPort		  1
-		  DstBlock		  " Terminator "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  9
-		  SrcBlock		  " SFunction "
-		  SrcPort		  1
-		  DstBlock		  " Demux "
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Delay
-	      Name		      "Delay"
-	      SID		      "1371"
-	      Ports		      [1, 1]
-	      Position		      [915, 193, 950, 227]
-	      ZOrder		      50
-	      Commented		      "through"
-	      InputPortMap	      "u0"
-	      DelayLength	      "4"
-	      InitialCondition	      "0"
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      Delay
-	      Name		      "Delay1"
-	      SID		      "1372"
-	      Ports		      [1, 1]
-	      Position		      [915, 278, 950, 312]
-	      ZOrder		      51
-	      Commented		      "through"
-	      InputPortMap	      "u0"
-	      DelayLength	      "4"
-	      InitialCondition	      "0"
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      DiscreteFilter
-	      Name		      "Discrete Filter1"
-	      SID		      "921"
-	      Ports		      [1, 1]
-	      Position		      [790, 192, 850, 228]
-	      ZOrder		      48
-	      InputPortMap	      "u0"
-	      Numerator		      "[0 0.1454]"
-	      Denominator	      "[1 -0.8546]"
-	      InitialStates	      "[0, 0, -1]"
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      DiscreteFilter
-	      Name		      "Discrete Filter2"
-	      SID		      "922"
-	      Ports		      [1, 1]
-	      Position		      [790, 277, 850, 313]
-	      ZOrder		      49
-	      InputPortMap	      "u0"
-	      Numerator		      "[0 0.1454]"
-	      Denominator	      "[1 -0.8546]"
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      DiscreteIntegrator
-	      Name		      "Discrete-Time\nIntegrator"
-	      SID		      "835"
-	      Ports		      [1, 1]
-	      Position		      [765, 407, 800, 443]
-	      ZOrder		      30
-	      InitialConditionSetting "State (most efficient)"
-	      SampleTime	      "-1"
-	      ICPrevOutput	      "DiscIntNeverNeededParam"
-	      ICPrevScaledInput	      "DiscIntNeverNeededParam"
-	    }
-	    Block {
-	      BlockType		      DiscreteIntegrator
-	      Name		      "Discrete-Time\nIntegrator2"
-	      SID		      "839"
-	      Ports		      [1, 1]
-	      Position		      [595, 407, 630, 443]
-	      ZOrder		      34
-	      InitialConditionSetting "State (most efficient)"
-	      SampleTime	      "-1"
-	      ICPrevOutput	      "DiscIntNeverNeededParam"
-	      ICPrevScaledInput	      "DiscIntNeverNeededParam"
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground"
-	      SID		      "664"
-	      Position		      [605, 340, 625, 360]
-	      ZOrder		      23
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground1"
-	      SID		      "665"
-	      Position		      [605, 145, 625, 165]
-	      ZOrder		      24
-	    }
-	    Block {
-	      BlockType		      Integrator
-	      Name		      "Integrator"
-	      SID		      "844"
-	      Ports		      [1, 1]
-	      Position		      [240, 360, 270, 390]
-	      ZOrder		      39
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope"
-	      SID		      "836"
-	      Ports		      [1]
-	      Position		      [845, 409, 875, 441]
-	      ZOrder		      31
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData1
-	      YMin		      -0.0001
-	      YMax		      0.00021
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [680 330 1240 750]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope2"
-	      SID		      "840"
-	      Ports		      [1]
-	      Position		      [670, 409, 700, 441]
-	      ZOrder		      35
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData3
-	      YMin		      -1.00000
-	      YMax		      1.00000
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [680 330 1240 750]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope5"
-	      SID		      "845"
-	      Ports		      [1]
-	      Position		      [295, 359, 325, 391]
-	      ZOrder		      40
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData6
-	      YMin		      -1.00000
-	      YMax		      1.00000
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [306 114 866 534]
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum"
-	      SID		      "666"
-	      Ports		      [2, 1]
-	      Position		      [715, 285, 735, 305]
-	      ZOrder		      7
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum1"
-	      SID		      "667"
-	      Ports		      [2, 1]
-	      Position		      [715, 200, 735, 220]
-	      ZOrder		      8
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum2"
-	      SID		      "668"
-	      Ports		      [2, 1]
-	      Position		      [625, 285, 645, 305]
-	      ZOrder		      11
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum3"
-	      SID		      "669"
-	      Ports		      [2, 1]
-	      Position		      [625, 200, 645, 220]
-	      ZOrder		      12
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "accelerometer_noise"
-	      SID		      "670"
-	      Position		      [655, 105, 685, 135]
-	      ZOrder		      2
-	      Mean		      "zeros(3,1)"
-	      Variance		      "[ 3e-7 ; 3.3e-7 ; 7.2e-7 ] "
-	      Seed		      "[0,1,2]"
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "accelerometer_quantizer"
-	      SID		      "671"
-	      Position		      [1030, 195, 1060, 225]
-	      ZOrder		      9
-	      ForegroundColor	      "red"
-	      QuantizationInterval    "2.4400e-04"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "accelerometer_sampling"
-	      SID		      "672"
-	      Position		      [510, 195, 545, 225]
-	      ZOrder		      15
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "gyroscope_noise"
-	      SID		      "673"
-	      Position		      [655, 335, 685, 365]
-	      ZOrder		      6
-	      Mean		      "zeros(3,1)"
-	      Variance		      "[ 2.2e-8 ; 1.1e-7 ; 2.4e-8 ]"
-	      Seed		      "[0,1,2]"
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "gyroscope_qunatizer"
-	      SID		      "674"
-	      Position		      [1030, 280, 1060, 310]
-	      ZOrder		      10
-	      ForegroundColor	      "red"
-	      QuantizationInterval    "1.1e-3"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "gyroscope_sampling"
-	      SID		      "675"
-	      Position		      [510, 280, 545, 310]
-	      ZOrder		      16
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      Constant
-	      Name		      "r_oc"
-	      SID		      "676"
-	      Position		      [30, 307, 95, 333]
-	      ZOrder		      28
-	      Value		      "zeros(3,1)"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accelerometer"
-	      SID		      "677"
-	      Position		      [1135, 203, 1165, 217]
-	      ZOrder		      29
-	      ForegroundColor	      "red"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "gyroscope"
-	      SID		      "678"
-	      Position		      [1135, 288, 1165, 302]
-	      ZOrder		      21
-	      ForegroundColor	      "red"
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "accelerometer_noise"
-	      SrcPort		      1
-	      Points		      [35, 0]
-	      DstBlock		      "Sum1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "Sum2"
-	      SrcPort		      1
-	      DstBlock		      "Sum"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Sum3"
-	      SrcPort		      1
-	      DstBlock		      "Sum1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "gyroscope_noise"
-	      SrcPort		      1
-	      Points		      [35, 0]
-	      Branch {
-		ZOrder			87
-		DstBlock		"Sum"
-		DstPort			2
-	      }
-	      Branch {
-		ZOrder			35
-		Points			[0, 75]
-		DstBlock		"Discrete-Time\nIntegrator"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      11
-	      SrcBlock		      "gyroscope_sampling"
-	      SrcPort		      1
-	      Points		      [30, 0]
-	      Branch {
-		ZOrder			85
-		DstBlock		"Sum2"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			45
-		DstBlock		"Discrete-Time\nIntegrator2"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      12
-	      SrcBlock		      "accelerometer_sampling"
-	      SrcPort		      1
-	      DstBlock		      "Sum3"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      13
-	      SrcBlock		      "Ground"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum2"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      14
-	      SrcBlock		      "Ground1"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      15
-	      SrcBlock		      "B_vo_dot"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      16
-	      SrcBlock		      "B_vo"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      17
-	      SrcBlock		      "B_Omega"
-	      SrcPort		      1
-	      Points		      [48, 0]
-	      Branch {
-		ZOrder			50
-		Points			[0, 125]
-		DstBlock		"Integrator"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			49
-		DstBlock		"\n\n\n\n\n\n\n"
-		DstPort			3
-	      }
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "B_g"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      4
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "r_oc"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      5
-	    }
-	    Line {
-	      ZOrder		      30
-	      SrcBlock		      "\n\n\n\n\n\n\n"
-	      SrcPort		      2
-	      DstBlock		      "gyroscope_sampling"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      31
-	      SrcBlock		      "\n\n\n\n\n\n\n"
-	      SrcPort		      1
-	      DstBlock		      "accelerometer_sampling"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      36
-	      SrcBlock		      "Discrete-Time\nIntegrator"
-	      SrcPort		      1
-	      DstBlock		      "Scope"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      40
-	      SrcBlock		      "Discrete-Time\nIntegrator2"
-	      SrcPort		      1
-	      DstBlock		      "Scope2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      48
-	      SrcBlock		      "Integrator"
-	      SrcPort		      1
-	      DstBlock		      "Scope5"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      124
-	      SrcBlock		      "Sum1"
-	      SrcPort		      1
-	      DstBlock		      "Discrete Filter1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      126
-	      SrcBlock		      "Sum"
-	      SrcPort		      1
-	      DstBlock		      "Discrete Filter2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      128
-	      SrcBlock		      "accelerometer_quantizer"
-	      SrcPort		      1
-	      DstBlock		      "accelerometer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      130
-	      SrcBlock		      "gyroscope_qunatizer"
-	      SrcPort		      1
-	      DstBlock		      "gyroscope"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      127
-	      SrcBlock		      "Discrete Filter1"
-	      SrcPort		      1
-	      DstBlock		      "Delay"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      129
-	      SrcBlock		      "Discrete Filter2"
-	      SrcPort		      1
-	      DstBlock		      "Delay1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      133
-	      SrcBlock		      "Delay"
-	      SrcPort		      1
-	      DstBlock		      "accelerometer_quantizer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      134
-	      SrcBlock		      "Delay1"
-	      SrcPort		      1
-	      DstBlock		      "gyroscope_qunatizer"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "MATLAB Function"
-	  SID			  "1389"
-	  Ports			  [3, 1]
-	  Position		  [1885, 897, 2075, 1113]
-	  ZOrder		  343
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  System {
-	    Name		    "MATLAB Function"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "23"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_pitch"
-	      SID		      "1389::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_roll"
-	      SID		      "1389::22"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_rates_gyro"
-	      SID		      "1389::23"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      14
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "1389::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "1389::19"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 17"
-	      Ports		      [3, 2]
-	      Position		      [180, 100, 230, 180]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[3 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_angles_IMU"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "1389::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_angles_IMU"
-	      SID		      "1389::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      14
-	      SrcBlock		      "accel_pitch"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      15
-	      SrcBlock		      "accel_roll"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      16
-	      SrcBlock		      "euler_rates_gyro"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "euler_angles_IMU"
-	      ZOrder		      17
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_angles_IMU"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "MATLAB Function1"
-	  SID			  "1407"
-	  Ports			  [1, 2]
-	  Position		  [1520, 196, 1625, 329]
-	  ZOrder		  350
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  System {
-	    Name		    "MATLAB Function1"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "22"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_reading"
-	      SID		      "1407::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "1407::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "1407::19"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 18"
-	      Ports		      [1, 3]
-	      Position		      [180, 100, 230, 180]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[1 3]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"accel_pitch"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"accel_roll"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "1407::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accel_pitch"
-	      SID		      "1407::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accel_roll"
-	      SID		      "1407::22"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "accel_reading"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "accel_pitch"
-	      ZOrder		      10
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "accel_pitch"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "accel_roll"
-	      ZOrder		      11
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "accel_roll"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      12
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      13
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Mux
-	  Name			  "Mux"
-	  SID			  "1345"
-	  Ports			  [2, 1]
-	  Position		  [2180, 536, 2185, 574]
-	  ZOrder		  330
-	  ShowName		  off
-	  Inputs		  "2"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "OptiTrack Camera System\n\n       "
-	  SID			  "681"
-	  Ports			  [2, 2]
-	  Position		  [1255, 1296, 1495, 1389]
-	  ZOrder		  299
-	  ForegroundColor	  "yellow"
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    33
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^{E}r_o', 'texmode', 'on');\nport_label('input', 2, '\\psi', 'texmode', 'on"
-	    "');\nport_label('output', 1, '^{E}r_o camera', 'texmode', 'on');\nport_label('output', 2, '\\psi camera', 'texmod"
-	    "e', 'on');\ndisp('OptiTrack Camera System', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "OptiTrack Camera System\n\n       "
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "E_ro"
-	      SID		      "682"
-	      Position		      [295, 238, 325, 252]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw"
-	      SID		      "683"
-	      Position		      [295, 338, 325, 352]
-	      ZOrder		      4
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "E_ro_noise"
-	      SID		      "684"
-	      Position		      [545, 175, 575, 205]
-	      ZOrder		      30
-	      Mean		      "zeros(3,1)"
-	      Variance		      "[ 7.9664e-10 ; 1.1928e-10 ; 5.0636e-10 ] "
-	      Seed		      "[0,1,2]"
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "E_ro_quantizer"
-	      SID		      "685"
-	      Position		      [685, 230, 715, 260]
-	      ZOrder		      34
-	      QuantizationInterval    "2.4400e-04"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "E_ro_sampling"
-	      SID		      "686"
-	      Position		      [410, 230, 445, 260]
-	      ZOrder		      38
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground1"
-	      SID		      "687"
-	      Position		      [465, 180, 485, 200]
-	      ZOrder		      42
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground2"
-	      SID		      "688"
-	      Position		      [465, 390, 485, 410]
-	      ZOrder		      56
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum1"
-	      SID		      "689"
-	      Ports		      [2, 1]
-	      Position		      [605, 235, 625, 255]
-	      ZOrder		      33
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum3"
-	      SID		      "690"
-	      Ports		      [2, 1]
-	      Position		      [485, 235, 505, 255]
-	      ZOrder		      37
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum4"
-	      SID		      "691"
-	      Ports		      [2, 1]
-	      Position		      [605, 335, 625, 355]
-	      ZOrder		      47
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum6"
-	      SID		      "692"
-	      Ports		      [2, 1]
-	      Position		      [485, 335, 505, 355]
-	      ZOrder		      51
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "yaw_noise"
-	      SID		      "693"
-	      Position		      [545, 365, 575, 395]
-	      ZOrder		      46
-	      Variance		      "1.0783e-9"
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "yaw_quantizer"
-	      SID		      "694"
-	      Position		      [685, 330, 715, 360]
-	      ZOrder		      50
-	      QuantizationInterval    "1.1e-3"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "yaw_sampling"
-	      SID		      "695"
-	      Position		      [410, 330, 445, 360]
-	      ZOrder		      54
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "E_ro_camera"
-	      SID		      "696"
-	      Position		      [800, 238, 830, 252]
-	      ZOrder		      43
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "yaw_camera"
-	      SID		      "697"
-	      Position		      [800, 338, 830, 352]
-	      ZOrder		      55
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "E_ro_noise"
-	      SrcPort		      1
-	      Points		      [35, 0]
-	      DstBlock		      "Sum1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "Sum3"
-	      SrcPort		      1
-	      DstBlock		      "Sum1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "Sum1"
-	      SrcPort		      1
-	      DstBlock		      "E_ro_quantizer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "E_ro_sampling"
-	      SrcPort		      1
-	      DstBlock		      "Sum3"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Ground1"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "Sum4"
-	      SrcPort		      1
-	      DstBlock		      "yaw_quantizer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "Sum6"
-	      SrcPort		      1
-	      DstBlock		      "Sum4"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      10
-	      SrcBlock		      "yaw_noise"
-	      SrcPort		      1
-	      Points		      [35, 0]
-	      DstBlock		      "Sum4"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      11
-	      SrcBlock		      "yaw_sampling"
-	      SrcPort		      1
-	      DstBlock		      "Sum6"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      12
-	      SrcBlock		      "Ground2"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum6"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      17
-	      SrcBlock		      "yaw"
-	      SrcPort		      1
-	      DstBlock		      "yaw_sampling"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "E_ro"
-	      SrcPort		      1
-	      DstBlock		      "E_ro_sampling"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "E_ro_quantizer"
-	      SrcPort		      1
-	      DstBlock		      "E_ro_camera"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      20
-	      SrcBlock		      "yaw_quantizer"
-	      SrcPort		      1
-	      DstBlock		      "yaw_camera"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Raw Accelerometer Data"
-	  SID			  "1258"
-	  Ports			  [1, 1]
-	  Position		  [1030, 457, 1185, 503]
-	  ZOrder		  317
-	  ForegroundColor	  "magenta"
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Variant		  on
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    34
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "disp('Raw Accelerometer Data', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Raw Accelerometer Data"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "175"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "raw_accel_model"
-	      SID		      "1259"
-	      Position		      [20, 128, 50, 142]
-	      ZOrder		      288
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Feedback"
-	      SID		      "1260"
-	      Ports		      [1, 1]
-	      Position		      [145, 155, 340, 185]
-	      ZOrder		      287
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==0"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		35
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Raw Accelerometer Data from Model', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Feedback"
-		Location		[-7, -7, 1288, 688]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "raw_accel_model"
-		  SID			  "1261"
-		  Position		  [105, 103, 135, 117]
-		  ZOrder		  2
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "raw_accel"
-		  SID			  "1262"
-		  Position		  [360, 103, 390, 117]
-		  ZOrder		  -2
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "raw_accel_model"
-		  SrcPort		  1
-		  DstBlock		  "raw_accel"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Raw Accelerometer Data "
-	      SID		      "1263"
-	      Ports		      [0, 1]
-	      Position		      [175, 75, 305, 105]
-	      ZOrder		      279
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==1"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		36
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Raw Accelerometer Data', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Raw Accelerometer Data "
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  FromWorkspace
-		  Name			  "From\nWorkspace5"
-		  SID			  "1264"
-		  Position		  [5, 18, 105, 42]
-		  ZOrder		  210
-		  VariableName		  "raw_accel_data"
-		  SampleTime		  "Tq"
-		  ZeroCross		  on
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "raw_accel"
-		  SID			  "1265"
-		  Position		  [145, 23, 175, 37]
-		  ZOrder		  172
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "From\nWorkspace5"
-		  SrcPort		  1
-		  DstBlock		  "raw_accel"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "raw_accel"
-	      SID		      "1266"
-	      Position		      [405, 128, 435, 142]
-	      ZOrder		      -2
-	      ForegroundColor	      "magenta"
-	      IconDisplay	      "Port number"
-	    }
-	    Annotation {
-	      SID		      "1267"
-	      Name		      "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">"
-	      "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap"
-	      "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n"
-	      "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde"
-	      "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m"
-	      "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco"
-	      "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;"
-	      "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti"
-	      "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H"
-	      "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b"
-	      "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st"
-	      "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co"
-	      "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin"
-	      "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo"
-	      "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>"
-	      Tag		      "VSSAddChoiceText"
-	      Position		      [71, 28, 448, 69]
-	      InternalMargins	      [0, 0, 0, 0]
-	      FixedHeight	      off
-	      FixedWidth	      off
-	      HorizontalAlignment     "left"
-	      Interpreter	      "rich"
-	      ZOrder		      -1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Raw Gyroscope Data"
-	  SID			  "1268"
-	  Ports			  [1, 1]
-	  Position		  [1030, 587, 1185, 633]
-	  ZOrder		  318
-	  ForegroundColor	  "magenta"
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Variant		  on
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    37
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "disp('Raw Gyroscope Data', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Raw Gyroscope Data"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "175"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "raw_gyro_model"
-	      SID		      "1269"
-	      Position		      [40, 128, 70, 142]
-	      ZOrder		      288
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Feedback"
-	      SID		      "1270"
-	      Ports		      [1, 1]
-	      Position		      [160, 153, 330, 187]
-	      ZOrder		      287
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==0"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		38
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Raw Gyroscope Data from Model', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Feedback"
-		Location		[633, 0, 1286, 687]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "raw_gyro_model"
-		  SID			  "1271"
-		  Position		  [105, 103, 135, 117]
-		  ZOrder		  2
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "raw_gyro"
-		  SID			  "1272"
-		  Position		  [360, 103, 390, 117]
-		  ZOrder		  -2
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "raw_gyro_model"
-		  SrcPort		  1
-		  DstBlock		  "raw_gyro"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Raw Gyroscope Data "
-	      SID		      "1273"
-	      Ports		      [0, 1]
-	      Position		      [180, 77, 310, 113]
-	      ZOrder		      279
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==1"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		39
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Raw Gyroscope Data', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Raw Gyroscope Data "
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  FromWorkspace
-		  Name			  "From\nWorkspace5"
-		  SID			  "1274"
-		  Position		  [145, 53, 230, 77]
-		  ZOrder		  210
-		  VariableName		  "raw_accel_data"
-		  SampleTime		  "Tq"
-		  ZeroCross		  on
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "raw_gyro"
-		  SID			  "1275"
-		  Position		  [295, 58, 325, 72]
-		  ZOrder		  172
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "From\nWorkspace5"
-		  SrcPort		  1
-		  DstBlock		  "raw_gyro"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "raw_gyro"
-	      SID		      "1276"
-	      Position		      [405, 128, 435, 142]
-	      ZOrder		      -2
-	      ForegroundColor	      "magenta"
-	      IconDisplay	      "Port number"
-	    }
-	    Annotation {
-	      SID		      "1277"
-	      Name		      "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">"
-	      "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap"
-	      "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n"
-	      "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde"
-	      "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m"
-	      "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco"
-	      "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;"
-	      "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti"
-	      "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H"
-	      "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b"
-	      "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st"
-	      "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co"
-	      "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin"
-	      "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo"
-	      "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>"
-	      Tag		      "VSSAddChoiceText"
-	      Position		      [71, 28, 448, 69]
-	      InternalMargins	      [0, 0, 0, 0]
-	      FixedHeight	      off
-	      FixedWidth	      off
-	      HorizontalAlignment     "left"
-	      Interpreter	      "rich"
-	      ZOrder		      -1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  ZeroOrderHold
-	  Name			  "Sample"
-	  SID			  "936"
-	  Position		  [1640, 1305, 1675, 1335]
-	  ZOrder		  313
-	  ForegroundColor	  "green"
-	  SampleTime		  "Tc"
-	}
-	Block {
-	  BlockType		  ZeroOrderHold
-	  Name			  "Sample1"
-	  SID			  "937"
-	  Position		  [1640, 1350, 1675, 1380]
-	  ZOrder		  314
-	  ForegroundColor	  "green"
-	  SampleTime		  "Tc"
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope"
-	  SID			  "737"
-	  Ports			  [1]
-	  Position		  [1315, 559, 1345, 591]
-	  ZOrder		  270
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData1
-	  YMin			  -0.00277
-	  YMax			  0.00209
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [680 330 1240 750]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope1"
-	  SID			  "738"
-	  Ports			  [1]
-	  Position		  [1315, 499, 1345, 531]
-	  ZOrder		  271
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData2
-	  YMin			  -2.04337
-	  YMax			  0.22704
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1909 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope2"
-	  SID			  "1386"
-	  Ports			  [2]
-	  Position		  [1810, 221, 1840, 254]
-	  ZOrder		  340
-	  NumInputPorts		  "2"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData1
-	  YMin			  -1.867~-5
-	  YMax			  1.68089~5
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope3"
-	  SID			  "1387"
-	  Ports			  [2]
-	  Position		  [1810, 286, 1840, 319]
-	  ZOrder		  341
-	  NumInputPorts		  "2"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData2
-	  YMin			  -3.89902~-5
-	  YMax			  3.92383~5
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1909 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope4"
-	  SID			  "1388"
-	  Ports			  [2]
-	  Position		  [1720, 911, 1750, 944]
-	  ZOrder		  342
-	  NumInputPorts		  "2"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData3
-	  YMin			  -3.39538~-5
-	  YMax			  1.81736~5
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope5"
-	  SID			  "1403"
-	  Ports			  [2]
-	  Position		  [2525, 733, 2565, 782]
-	  ZOrder		  346
-	  NumInputPorts		  "2"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData4
-	  YMin			  -0.99149~-5
-	  YMax			  0.86243~5
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope6"
-	  SID			  "1406"
-	  Ports			  [2]
-	  Position		  [2525, 823, 2565, 872]
-	  ZOrder		  349
-	  NumInputPorts		  "2"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData5
-	  YMin			  -1.37391~-5
-	  YMax			  0.98927~5
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  S-Function
-	  Name			  "Soft Real Time"
-	  SID			  "742"
-	  Ports			  []
-	  Position		  [2008, 1540, 2095, 1571]
-	  ZOrder		  288
-	  ShowName		  off
-	  Commented		  "on"
-	  FunctionName		  "sfun_time"
-	  Parameters		  "x"
-	  SFunctionDeploymentMode off
-	  EnableBusSupport	  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    40
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "color('red')\ndisp('Soft Real Time')\n"
-	    Object {
-	      $PropName		      "Parameters"
-	      $ObjectID		      41
-	      $ClassName	      "Simulink.MaskParameter"
-	      Type		      "edit"
-	      Name		      "x"
-	      Prompt		      "Time Scaling Factor"
-	      Value		      "1"
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  ToWorkspace
-	  Name			  "To Workspace4"
-	  SID			  "1420"
-	  Ports			  [1]
-	  Position		  [1925, 1230, 2050, 1260]
-	  ZOrder		  351
-	  ShowName		  off
-	  VariableName		  "position_model"
-	  MaxDataPoints		  "inf"
-	  SaveFormat		  "Structure With Time"
-	  Save2DSignal		  "3-D array (concatenate along third dimension)"
-	  FixptAsFi		  on
-	  SampleTime		  "Tc"
-	}
-	Block {
-	  BlockType		  ToWorkspace
-	  Name			  "To Workspace5"
-	  SID			  "1256"
-	  Ports			  [1]
-	  Position		  [2360, 405, 2470, 435]
-	  ZOrder		  315
-	  ForegroundColor	  "red"
-	  VariableName		  "angle_IMU_reading"
-	  MaxDataPoints		  "inf"
-	  SaveFormat		  "Structure With Time"
-	  Save2DSignal		  "3-D array (concatenate along third dimension)"
-	  FixptAsFi		  on
-	  SampleTime		  "Tq"
-	}
-	Block {
-	  BlockType		  TransportDelay
-	  Name			  "Transport\nDelay"
-	  SID			  "933"
-	  Ports			  [1, 1]
-	  Position		  [1565, 1305, 1595, 1335]
-	  ZOrder		  310
-	  DelayTime		  "6e-3"
-	}
-	Block {
-	  BlockType		  TransportDelay
-	  Name			  "Transport\nDelay1"
-	  SID			  "935"
-	  Ports			  [1, 1]
-	  Position		  [1565, 1350, 1595, 1380]
-	  ZOrder		  312
-	  DelayTime		  "6e-3"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "euler_angles_filtered"
-	  SID			  "743"
-	  Position		  [2245, 548, 2275, 562]
-	  ZOrder		  262
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "euler_rates"
-	  SID			  "744"
-	  Position		  [1255, 653, 1290, 667]
-	  ZOrder		  259
-	  ForegroundColor	  "red"
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "current_position"
-	  SID			  "745"
-	  Position		  [1925, 1313, 1955, 1327]
-	  ZOrder		  289
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "IMU\n\n\n\n\n\n"
-	  SrcPort		  1
-	  DstBlock		  "Raw Accelerometer Data"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  4
-	  SrcBlock		  "IMU\n\n\n\n\n\n"
-	  SrcPort		  2
-	  DstBlock		  "Raw Gyroscope Data"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  8
-	  SrcBlock		  "B_vo"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  9
-	  SrcBlock		  "B_Omega"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  10
-	  SrcBlock		  "B_g"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  4
-	}
-	Line {
-	  ZOrder		  11
-	  SrcBlock		  "Calculate Pitch and Roll"
-	  SrcPort		  2
-	  Points		  [102, 0]
-	  Branch {
-	    ZOrder		    553
-	    Points		    [0, -175]
-	    DstBlock		    "Scope3"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    548
-	    Points		    [0, 60]
-	    DstBlock		    "Delay1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    245
-	    Points		    [76, 0]
-	    Branch {
-	      ZOrder		      597
-	      Points		      [0, 520]
-	      DstBlock		      "MATLAB Function"
-	      DstPort		      2
-	    }
-	    Branch {
-	      ZOrder		      596
-	      Points		      [27, 0]
-	      DstBlock		      "Complimentary Filter"
-	      DstPort		      2
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  16
-	  SrcBlock		  "Calculate Pitch and Roll"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  Branch {
-	    ZOrder		    552
-	    Points		    [0, -170]
-	    DstBlock		    "Scope2"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    551
-	    Points		    [173, 0]
-	    Branch {
-	      ZOrder		      595
-	      Points		      [0, 520]
-	      DstBlock		      "MATLAB Function"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      594
-	      DstBlock		      "Complimentary Filter"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  25
-	  SrcBlock		  "Delay1"
-	  SrcPort		  1
-	  Points		  [-89, 0; 0, -60]
-	  DstBlock		  "Calculate Pitch and Roll"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  33
-	  SrcBlock		  "First-Order\nHold"
-	  SrcPort		  1
-	  DstBlock		  "3D Graphical Simulation1"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  34
-	  SrcBlock		  "E_ro"
-	  SrcPort		  1
-	  Points		  [191, 0]
-	  Branch {
-	    ZOrder		    35
-	    Points		    [0, 120]
-	    DstBlock		    "3D Graphical Simulation"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    36
-	    DstBlock		    "OptiTrack Camera System\n\n       "
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  38
-	  SrcBlock		  "First-Order\nHold1"
-	  SrcPort		  1
-	  Points		  [20, 0; 0, -65]
-	  DstBlock		  "3D Graphical Simulation1"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  62
-	  SrcBlock		  "B_vo_dot"
-	  SrcPort		  1
-	  DstBlock		  "Delay2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  63
-	  SrcBlock		  "Delay2"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  45
-	  SrcBlock		  "OptiTrack Camera System\n\n       "
-	  SrcPort		  1
-	  Points		  [24, 0]
-	  Branch {
-	    ZOrder		    235
-	    DstBlock		    "Transport\nDelay"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    208
-	    Points		    [0, 225]
-	    DstBlock		    "First-Order\nHold1"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  209
-	  SrcBlock		  "OptiTrack Camera System\n\n       "
-	  SrcPort		  2
-	  Points		  [46, 0]
-	  Branch {
-	    ZOrder		    234
-	    Points		    [0, 85]
-	    DstBlock		    "First-Order\nHold"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    229
-	    DstBlock		    "Transport\nDelay1"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  226
-	  SrcBlock		  "Transport\nDelay"
-	  SrcPort		  1
-	  DstBlock		  "Sample"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  228
-	  SrcBlock		  "Transport\nDelay1"
-	  SrcPort		  1
-	  DstBlock		  "Sample1"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  230
-	  SrcBlock		  "Sample"
-	  SrcPort		  1
-	  Points		  [110, 0]
-	  Branch {
-	    ZOrder		    708
-	    Points		    [0, -75]
-	    DstBlock		    "To Workspace4"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    707
-	    DstBlock		    "current_position"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  295
-	  SrcBlock		  "Raw Accelerometer Data"
-	  SrcPort		  1
-	  Points		  [100, 0]
-	  Branch {
-	    ZOrder		    414
-	    Points		    [83, 0; 0, -65; 48, 0]
-	    Branch {
-	      ZOrder		      467
-	      Points		      [0, -150]
-	      DstBlock		      "MATLAB Function1"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      466
-	      DstBlock		      "Calculate Pitch and Roll"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    297
-	    Points		    [0, 35]
-	    DstBlock		    "Scope1"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  298
-	  SrcBlock		  "Raw Gyroscope Data"
-	  SrcPort		  1
-	  Points		  [30, 0]
-	  Branch {
-	    ZOrder		    413
-	    Points		    [66, 0]
-	    Branch {
-	      ZOrder		      6
-	      Points		      [74, 0]
-	      Branch {
-		ZOrder			561
-		Points			[0, 390]
-		DstBlock		"Aeb_c\n\n\n\n\n\n\n\n\n\n1"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			316
-		DstBlock		"Aeb\n\n\n\n\n\n\n\n\n\n"
-		DstPort			1
-	      }
-	    }
-	    Branch {
-	      ZOrder		      5
-	      Points		      [0, -35]
-	      DstBlock		      "Scope"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    160
-	    Points		    [0, 50]
-	    DstBlock		    "euler_rates"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  342
-	  SrcBlock		  "Delay"
-	  SrcPort		  1
-	  Points		  [-179, 0]
-	  Branch {
-	    ZOrder		    562
-	    Points		    [0, -75]
-	    DstBlock		    "Complimentary Filter"
-	    DstPort		    4
-	  }
-	  Branch {
-	    ZOrder		    565
-	    Points		    [0, 115; -374, 0; 0, 200]
-	    DstBlock		    "Aeb_c\n\n\n\n\n\n\n\n\n\n1"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    411
-	    Points		    [-339, 0; 0, -75]
-	    DstBlock		    "Aeb\n\n\n\n\n\n\n\n\n\n"
-	    DstPort		    2
-	  }
-	}
-	Line {
-	  ZOrder		  416
-	  SrcBlock		  "euler_angles"
-	  SrcPort		  1
-	  DstBlock		  "Demux"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  417
-	  SrcBlock		  "Demux"
-	  SrcPort		  3
-	  DstBlock		  "OptiTrack Camera System\n\n       "
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  419
-	  SrcBlock		  "Sample1"
-	  SrcPort		  1
-	  Points		  [483, 0; 0, -800]
-	  DstBlock		  "Mux"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  420
-	  SrcBlock		  "Mux"
-	  SrcPort		  1
-	  DstBlock		  "euler_angles_filtered"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  335
-	  SrcBlock		  "Complimentary Filter"
-	  SrcPort		  1
-	  Points		  [54, 0]
-	  Branch {
-	    ZOrder		    665
-	    DstBlock		    "Mux"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    546
-	    Points		    [0, -125]
-	    DstBlock		    "To Workspace5"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    533
-	    Points		    [0, 200]
-	    Branch {
-	      ZOrder		      667
-	      DstBlock		      "Demux1"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      666
-	      DstBlock		      "Delay"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  407
-	  SrcBlock		  "Aeb\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  Points		  [45, 0]
-	  Branch {
-	    ZOrder		    560
-	    DstBlock		    "Scope4"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    558
-	    Points		    [108, 0]
-	    Branch {
-	      ZOrder		      600
-	      Points		      [0, 435]
-	      DstBlock		      "MATLAB Function"
-	      DstPort		      3
-	    }
-	    Branch {
-	      ZOrder		      599
-	      Points		      [2, 0; 0, -55]
-	      DstBlock		      "Complimentary Filter"
-	      DstPort		      3
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  557
-	  SrcBlock		  "Aeb_c\n\n\n\n\n\n\n\n\n\n1"
-	  SrcPort		  1
-	  Points		  [35, 0; 0, -95]
-	  DstBlock		  "Scope4"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  604
-	  SrcBlock		  "MATLAB Function"
-	  SrcPort		  1
-	  Points		  [40, 0; 0, -70]
-	  DstBlock		  "Demux2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  605
-	  SrcBlock		  "Demux1"
-	  SrcPort		  1
-	  Points		  [105, 0; 0, 10]
-	  DstBlock		  "Scope5"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  606
-	  SrcBlock		  "Demux2"
-	  SrcPort		  1
-	  Points		  [118, 0; 0, -155]
-	  DstBlock		  "Scope5"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  607
-	  SrcBlock		  "Demux1"
-	  SrcPort		  2
-	  Points		  [62, 0; 0, 80]
-	  DstBlock		  "Scope6"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  608
-	  SrcBlock		  "Demux2"
-	  SrcPort		  2
-	  Points		  [174, 0; 0, -85]
-	  DstBlock		  "Scope6"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  611
-	  SrcBlock		  "MATLAB Function1"
-	  SrcPort		  1
-	  DstBlock		  "Scope2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  614
-	  SrcBlock		  "MATLAB Function1"
-	  SrcPort		  2
-	  DstBlock		  "Scope3"
-	  DstPort		  1
-	}
-      }
-    }
-    Block {
-      BlockType		      SubSystem
-      Name		      "Actuation"
-      SID		      "436"
-      Ports		      [1, 6]
-      Position		      [955, 426, 1205, 654]
-      ZOrder		      71
-      ShowName		      off
-      RequestExecContextInheritance off
-      Variant		      off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		42
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('input', 1, 'P', 'texmode', 'on');\nport_label('output', 1, '^{B}Omega', 'texmode', 'on');\npor"
-	"t_label('output', 2, '\\Theta', 'texmode', 'on');\nport_label('output', 3, '^{B}v_o', 'texmode', 'on');\nport_label('"
-	"output', 4, '^{E}r_o', 'texmode', 'on');\nport_label('output', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('outpu"
-	"t', 6, '^{B}g', 'texmode', 'on');\ndisp('Actuation', 'texmode', 'on'); "
-      }
-      System {
-	Name			"Actuation"
-	Location		[-8, -8, 1928, 1048]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"125"
-	Block {
-	  BlockType		  Inport
-	  Name			  "P"
-	  SID			  "437"
-	  Position		  [-105, 393, -75, 407]
-	  ZOrder		  -1
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SID			  "446"
-	  Ports			  [2, 1]
-	  Position		  [1395, 303, 1630, 452]
-	  ZOrder		  81
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    43
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^B\\Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode',"
-	    " 'on');\nport_label('output', 1, 'd\\Theta/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "25"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_omega"
-	      SID		      "446::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles"
-	      SID		      "446::22"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "446::24"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      15
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "446::23"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 7"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      14
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_rates"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "446::25"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      16
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_rates"
-	      SID		      "446::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "B_omega"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "euler_rates"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_rates"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux1"
-	  SID			  "449"
-	  Ports			  [1, 3]
-	  Position		  [1830, 526, 1835, 574]
-	  ZOrder		  107
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "x position"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "y position"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "z position"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux2"
-	  SID			  "450"
-	  Ports			  [1, 3]
-	  Position		  [1830, 301, 1835, 349]
-	  ZOrder		  109
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Roll"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Pitch"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Yaw"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux3"
-	  SID			  "451"
-	  Ports			  [1, 3]
-	  Position		  [1830, 406, 1835, 454]
-	  ZOrder		  117
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Body x velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Body y velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Body z velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux4"
-	  SID			  "452"
-	  Ports			  [1, 3]
-	  Position		  [1830, 161, 1835, 209]
-	  ZOrder		  115
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Body roll velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Body pitch velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Body yaw velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux5"
-	  SID			  "453"
-	  Ports			  [1, 3]
-	  Position		  [1830, 641, 1835, 689]
-	  ZOrder		  119
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Body x acceleration"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Body y acceleration"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Body z acceleration"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "ESC System"
-	  SID			  "442"
-	  Ports			  [1, 1]
-	  Position		  [35, 282, 290, 518]
-	  ZOrder		  36
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    44
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'P', 'texmode', 'on');\nport_label('output', 1, 'Vb_{eff}', 'texmode', 'on')"
-	    ";\ndisp('ESC System');"
-	  }
-	  System {
-	    Name		    "ESC System"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "37"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "P"
-	      SID		      "442::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "442::36"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      17
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "442::35"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 4"
-	      Ports		      [1, 2]
-	      Position		      [180, 105, 230, 165]
-	      ZOrder		      16
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "Pmax,Pmin,Vb"
-	      PortCounts	      "[1 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"Vb_eff"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "442::37"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      18
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "Vb_eff"
-	      SID		      "442::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      34
-	      SrcBlock		      "P"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "Vb_eff"
-	      ZOrder		      35
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "Vb_eff"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      36
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      37
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Gravity\n\n"
-	  SID			  "443"
-	  Ports			  [0, 1]
-	  Position		  [335, 664, 485, 786]
-	  ZOrder		  96
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    45
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('output', 1, '^EF_g', 'texmode', 'on');\nfprintf('Gravity');\n"
-	  }
-	  System {
-	    Name		    "Gravity\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "30"
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "443::28"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      19
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      " Ground "
-	      SID		      "443::30"
-	      Position		      [20, 121, 40, 139]
-	      ZOrder		      21
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "443::27"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 1"
-	      Ports		      [1, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      18
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "g,m"
-	      PortCounts	      "[1 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"E_Fg"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "443::29"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      20
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "E_Fg"
-	      SID		      "443::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      Name		      "E_Fg"
-	      ZOrder		      1
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "E_Fg"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      " Ground "
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator"
-	  SID			  "454"
-	  Ports			  [1, 1]
-	  Position		  [740, 340, 770, 370]
-	  ZOrder		  49
-	  InitialCondition	  "[omega0_o, omega1_o, omega2_o, omega3_o]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator1"
-	  SID			  "455"
-	  Ports			  [1, 1]
-	  Position		  [1225, 445, 1255, 475]
-	  ZOrder		  53
-	  InitialCondition	  "[x_vel_o; y_vel_o; z_vel_o]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator2"
-	  SID			  "456"
-	  Ports			  [1, 1]
-	  Position		  [1225, 325, 1255, 355]
-	  ZOrder		  54
-	  InitialCondition	  "[rollrate_o; pitchrate_o; yawrate_o]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator3"
-	  SID			  "457"
-	  Ports			  [1, 1]
-	  Position		  [1685, 590, 1715, 620]
-	  ZOrder		  98
-	  InitialCondition	  "[x_o; y_o; z_o]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator4"
-	  SID			  "458"
-	  Ports			  [1, 1]
-	  Position		  [1685, 365, 1715, 395]
-	  ZOrder		  77
-	  InitialCondition	  "[roll_o; pitch_o; yaw_o]"
-	  ContinuousStateAttributes "['phi' 'theta' 'psi']"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Lbe\n\n\n\n\n\n"
-	  SID			  "444"
-	  Ports			  [2, 1]
-	  Position		  [1395, 499, 1630, 706]
-	  ZOrder		  75
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    46
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^Bv_o', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on"
-	    "');\nport_label('output', 1, '^Ev_o', 'texmode', 'on');\ndisp('L_{EB}', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Lbe\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "31"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo"
-	      SID		      "444::24"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      15
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles"
-	      SID		      "444::28"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      19
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "444::30"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      21
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "444::29"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 2"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      20
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"E_ro"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "444::31"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      22
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "E_ro"
-	      SID		      "444::26"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      17
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "B_vo"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "E_ro"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "E_ro"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SID			  "447"
-	  Ports			  [2, 2]
-	  Position		  [600, 694, 770, 816]
-	  ZOrder		  97
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    47
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^EF_g', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on"
-	    "');\nport_label('output', 1, '^BF_g', 'texmode', 'on');\nport_label('output', 2, '^Bg', 'texmode', 'on');\ndisp('"
-	    "L_{BE}', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "33"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "E_Fg"
-	      SID		      "447::24"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      15
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles"
-	      SID		      "447::28"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      19
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "447::30"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      21
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "447::29"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 8"
-	      Ports		      [2, 3]
-	      Position		      [180, 100, 230, 180]
-	      ZOrder		      20
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "m"
-	      PortCounts	      "[2 3]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"B_Fg"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"B_g"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "447::31"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      22
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_Fg"
-	      SID		      "447::26"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      17
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_g"
-	      SID		      "447::32"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      23
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "E_Fg"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "B_Fg"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "B_Fg"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "B_g"
-	      ZOrder		      4
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "B_g"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Motor System"
-	  SID			  "441"
-	  Ports			  [2, 1]
-	  Position		  [420, 280, 640, 520]
-	  ZOrder		  48
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    48
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Vb_{eff}', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', "
-	    "'on');\nport_label('output', 1, '\\alpha', 'texmode', 'on');\ndisp('Motor System');\n"
-	  }
-	  System {
-	    Name		    "Motor System"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "35"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Vb_eff"
-	      SID		      "441::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "w"
-	      SID		      "441::35"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      20
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "441::32"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      17
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "441::31"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 5"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      16
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "If,Jreq,Kd,Kq,Kv,Rm"
-	      PortCounts	      "[2 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"w_dot"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "441::33"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      18
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "w_dot"
-	      SID		      "441::23"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      14
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      33
-	      SrcBlock		      "Vb_eff"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      34
-	      SrcBlock		      "w"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "w_dot"
-	      ZOrder		      35
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "w_dot"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      36
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      37
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Rotor System\n\n\n\n\n\n\n\n"
-	  SID			  "758"
-	  Ports			  [5, 2]
-	  Position		  [945, 281, 1145, 519]
-	  ZOrder		  122
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    49
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '\\alpha', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', '"
-	    "on');\nport_label('input', 3, '^BF_g', 'texmode', 'on');\nport_label('input', 4, '^B\\Omega', 'texmode', 'on');\n"
-	    "port_label('input', 5, '^Bv_o', 'texmode', 'on');\nport_label('output', 1, '^Bd\\Omega/dt', 'texmode', 'on');\npo"
-	    "rt_label('output', 2, '^Bdv_o/dt', 'texmode', 'on');\ndisp('Rotor System', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Rotor System\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "51"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "w_dot"
-	      SID		      "758::27"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      18
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "w"
-	      SID		      "758::28"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      19
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_Fg"
-	      SID		      "758::47"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      20
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_omega"
-	      SID		      "758::25"
-	      Position		      [20, 206, 40, 224]
-	      ZOrder		      16
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo"
-	      SID		      "758::24"
-	      Position		      [20, 246, 40, 264]
-	      ZOrder		      15
-	      Port		      "5"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "758::49"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      22
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "758::48"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 6"
-	      Ports		      [5, 3]
-	      Position		      [180, 100, 230, 220]
-	      ZOrder		      21
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "Jreq,Jxx,Jyy,Jzz,Kd,Kt,m,rhx,rhy,rhz"
-	      PortCounts	      "[5 3]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"B_omega_dot"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"B_vo_dot"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "758::50"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      23
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_omega_dot"
-	      SID		      "758::22"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      13
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_vo_dot"
-	      SID		      "758::5"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      -5
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      29
-	      SrcBlock		      "w_dot"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      30
-	      SrcBlock		      "w"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      31
-	      SrcBlock		      "B_Fg"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      32
-	      SrcBlock		      "B_omega"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      4
-	    }
-	    Line {
-	      ZOrder		      33
-	      SrcBlock		      "B_vo"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      5
-	    }
-	    Line {
-	      Name		      "B_omega_dot"
-	      ZOrder		      34
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "B_omega_dot"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "B_vo_dot"
-	      ZOrder		      35
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "B_vo_dot"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      36
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      37
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope"
-	  SID			  "459"
-	  Ports			  [1]
-	  Position		  [350, 279, 380, 311]
-	  ZOrder		  46
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData
-	  YMin			  -0.88633
-	  YMax			  7.97693
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope1"
-	  SID			  "460"
-	  Ports			  [1]
-	  Position		  [740, 229, 770, 261]
-	  ZOrder		  50
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData1
-	  YMin			  -4063.58997
-	  YMax			  3472.27662
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope10"
-	  SID			  "461"
-	  Ports			  [3]
-	  Position		  [1935, 303, 1975, 347]
-	  ZOrder		  108
-	  NumInputPorts		  "3"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData1
-	  YMin			  -1.00000~-1.00000~-1.00000
-	  YMax			  1.00000~1.00000~1.00000
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope11"
-	  SID			  "462"
-	  Ports			  [3]
-	  Position		  [1935, 163, 1975, 207]
-	  ZOrder		  114
-	  NumInputPorts		  "3"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData3
-	  YMin			  -1.00000~-1.00000~-1.00000
-	  YMax			  1.00000~1.00000~1.00000
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope2"
-	  SID			  "463"
-	  Ports			  [1]
-	  Position		  [890, 229, 920, 261]
-	  ZOrder		  51
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData2
-	  YMin			  -87.04326
-	  YMax			  669.47775
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope3"
-	  SID			  "464"
-	  Ports			  [3]
-	  Position		  [1935, 408, 1975, 452]
-	  ZOrder		  116
-	  NumInputPorts		  "3"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData2
-	  YMin			  -1.00000~-1.00000~-0.000000000000004
-	  YMax			  1.00000~1.00000~0.000000000000032
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope4"
-	  SID			  "465"
-	  Ports			  [3]
-	  Position		  [1935, 643, 1975, 687]
-	  ZOrder		  118
-	  NumInputPorts		  "3"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData4
-	  YMin			  -1.00000~-1.00000~0.0000000000000004
-	  YMax			  1.00000~1.00000~0.0000000000000024
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope5"
-	  SID			  "1050"
-	  Ports			  [1]
-	  Position		  [1335, 364, 1365, 396]
-	  ZOrder		  316
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData3
-	  YMin			  -0.66996
-	  YMax			  5.80636
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope6"
-	  SID			  "466"
-	  Ports			  [3]
-	  Position		  [1935, 528, 1975, 572]
-	  ZOrder		  79
-	  NumInputPorts		  "3"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  on
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData4
-	  YMin			  -1.00000~-1.00000~-0.00000000000004
-	  YMax			  1.00000~1.00000~0.00000000000032
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope7"
-	  SID			  "467"
-	  Ports			  [1]
-	  Position		  [600, 639, 630, 671]
-	  ZOrder		  99
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData1
-	  YMin			  -1.52545
-	  YMax			  13.7291
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope8"
-	  SID			  "468"
-	  Ports			  [1]
-	  Position		  [820, 629, 850, 661]
-	  ZOrder		  100
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData2
-	  YMin			  -14.59237
-	  YMax			  14.59237
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope9"
-	  SID			  "469"
-	  Ports			  [1]
-	  Position		  [1225, 229, 1255, 261]
-	  ZOrder		  102
-	  NumInputPorts		  "1"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData3
-	  YMin			  -1.00000
-	  YMax			  1.00000
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [1 76 1921 1039]
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_omega"
-	  SID			  "471"
-	  Position		  [1845, 238, 1875, 252]
-	  ZOrder		  61
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "euler_angles"
-	  SID			  "472"
-	  Position		  [1845, 373, 1875, 387]
-	  ZOrder		  91
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_vo"
-	  SID			  "473"
-	  Position		  [1845, 473, 1875, 487]
-	  ZOrder		  58
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "E_ro"
-	  SID			  "474"
-	  Position		  [1845, 598, 1875, 612]
-	  ZOrder		  88
-	  Port			  "4"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_vo_dot"
-	  SID			  "475"
-	  Position		  [1845, 718, 1875, 732]
-	  ZOrder		  103
-	  Port			  "5"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_g"
-	  SID			  "476"
-	  Position		  [1845, 778, 1875, 792]
-	  ZOrder		  104
-	  Port			  "6"
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "ESC System"
-	  SrcPort		  1
-	  Points		  [23, 0; 0, -60]
-	  Branch {
-	    ZOrder		    2
-	    Points		    [0, -45]
-	    DstBlock		    "Scope"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    3
-	    DstBlock		    "Motor System"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  4
-	  SrcBlock		  "Motor System"
-	  SrcPort		  1
-	  Points		  [40, 0; 0, -45]
-	  Branch {
-	    ZOrder		    5
-	    DstBlock		    "Integrator"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    6
-	    Points		    [0, -45]
-	    Branch {
-	      ZOrder		      101
-	      DstBlock		      "Rotor System\n\n\n\n\n\n\n\n"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      7
-	      Points		      [0, -65]
-	      DstBlock		      "Scope1"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  103
-	  SrcBlock		  "Rotor System\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  Points		  [39, 0]
-	  Branch {
-	    ZOrder		    15
-	    Points		    [0, -95]
-	    DstBlock		    "Scope9"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    16
-	    DstBlock		    "Integrator2"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  22
-	  SrcBlock		  "Integrator2"
-	  SrcPort		  1
-	  Points		  [55, 0]
-	  Branch {
-	    ZOrder		    105
-	    Points		    [0, 252; -416, 0; 0, -147]
-	    DstBlock		    "Rotor System\n\n\n\n\n\n\n\n"
-	    DstPort		    4
-	  }
-	  Branch {
-	    ZOrder		    23
-	    Points		    [0, -95; 454, 0]
-	    Branch {
-	      ZOrder		      24
-	      DstBlock		      "B_omega"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      25
-	      Points		      [0, -60]
-	      DstBlock		      "Demux4"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    27
-	    DstBlock		    "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  28
-	  SrcBlock		  "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  DstBlock		  "Integrator4"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  32
-	  SrcBlock		  "Lbe\n\n\n\n\n\n"
-	  SrcPort		  1
-	  DstBlock		  "Integrator3"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  33
-	  SrcBlock		  "Integrator3"
-	  SrcPort		  1
-	  Points		  [64, 0]
-	  Branch {
-	    ZOrder		    34
-	    Points		    [0, -55]
-	    DstBlock		    "Demux1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    35
-	    DstBlock		    "E_ro"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  36
-	  SrcBlock		  "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  Points		  [24, 0]
-	  Branch {
-	    ZOrder		    368
-	    Points		    [0, -80]
-	    DstBlock		    "Scope8"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    107
-	    Points		    [82, 0; 0, -325]
-	    DstBlock		    "Rotor System\n\n\n\n\n\n\n\n"
-	    DstPort		    3
-	  }
-	}
-	Line {
-	  ZOrder		  39
-	  SrcBlock		  "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  2
-	  DstBlock		  "B_g"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "y position"
-	  ZOrder		  45
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux1"
-	  SrcPort		  2
-	  DstBlock		  "Scope6"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "x position"
-	  ZOrder		  46
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux1"
-	  SrcPort		  1
-	  DstBlock		  "Scope6"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "z position"
-	  ZOrder		  47
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux1"
-	  SrcPort		  3
-	  DstBlock		  "Scope6"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Pitch"
-	  ZOrder		  57
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux2"
-	  SrcPort		  2
-	  DstBlock		  "Scope10"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Roll"
-	  ZOrder		  58
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux2"
-	  SrcPort		  1
-	  DstBlock		  "Scope10"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Yaw"
-	  ZOrder		  59
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux2"
-	  SrcPort		  3
-	  DstBlock		  "Scope10"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Body pitch velocity"
-	  ZOrder		  60
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux4"
-	  SrcPort		  2
-	  DstBlock		  "Scope11"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Body roll velocity"
-	  ZOrder		  61
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux4"
-	  SrcPort		  1
-	  DstBlock		  "Scope11"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Body yaw velocity"
-	  ZOrder		  62
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux4"
-	  SrcPort		  3
-	  DstBlock		  "Scope11"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Body y velocity"
-	  ZOrder		  63
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux3"
-	  SrcPort		  2
-	  DstBlock		  "Scope3"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Body x velocity"
-	  ZOrder		  64
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux3"
-	  SrcPort		  1
-	  DstBlock		  "Scope3"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Body z velocity"
-	  ZOrder		  65
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux3"
-	  SrcPort		  3
-	  DstBlock		  "Scope3"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Body y acceleration"
-	  ZOrder		  66
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux5"
-	  SrcPort		  2
-	  DstBlock		  "Scope4"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Body x acceleration"
-	  ZOrder		  67
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux5"
-	  SrcPort		  1
-	  DstBlock		  "Scope4"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Body z acceleration"
-	  ZOrder		  68
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux5"
-	  SrcPort		  3
-	  DstBlock		  "Scope4"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  69
-	  SrcBlock		  "Integrator1"
-	  SrcPort		  1
-	  Points		  [34, 0]
-	  Branch {
-	    ZOrder		    414
-	    Points		    [0, -80]
-	    DstBlock		    "Scope5"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    413
-	    Points		    [0, 90]
-	    Branch {
-	      ZOrder		      104
-	      Points		      [-370, 0; 0, -60]
-	      DstBlock		      "Rotor System\n\n\n\n\n\n\n\n"
-	      DstPort		      5
-	    }
-	    Branch {
-	      ZOrder		      71
-	      Points		      [76, 0]
-	      Branch {
-		ZOrder			72
-		DstBlock		"Lbe\n\n\n\n\n\n"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			73
-		Points			[0, -70; 401, 0]
-		Branch {
-		  ZOrder		  367
-		  Points		  [0, -50]
-		  DstBlock		  "Demux3"
-		  DstPort		  1
-		}
-		Branch {
-		  ZOrder		  75
-		  DstBlock		  "B_vo"
-		  DstPort		  1
-		}
-	      }
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  102
-	  SrcBlock		  "Rotor System\n\n\n\n\n\n\n\n"
-	  SrcPort		  2
-	  Points		  [27, 0]
-	  Branch {
-	    ZOrder		    205
-	    Points		    [0, 265; 607, 0]
-	    Branch {
-	      ZOrder		      201
-	      Points		      [0, -60]
-	      DstBlock		      "Demux5"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      200
-	      DstBlock		      "B_vo_dot"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    198
-	    DstBlock		    "Integrator1"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  48
-	  SrcBlock		  "Integrator4"
-	  SrcPort		  1
-	  Points		  [20, 0]
-	  Branch {
-	    ZOrder		    277
-	    Points		    [60, 0]
-	    Branch {
-	      ZOrder		      361
-	      DstBlock		      "euler_angles"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      360
-	      Points		      [0, -55]
-	      DstBlock		      "Demux2"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    52
-	    Points		    [0, 502; -385, 0]
-	    Branch {
-	      ZOrder		      352
-	      Points		      [0, -227]
-	      Branch {
-		ZOrder			54
-		DstBlock		"Lbe\n\n\n\n\n\n"
-		DstPort			2
-	      }
-	      Branch {
-		ZOrder			55
-		Points			[0, -240]
-		DstBlock		"Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-		DstPort			2
-	      }
-	    }
-	    Branch {
-	      ZOrder		      56
-	      Points		      [-787, 0; 0, -97]
-	      DstBlock		      "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	      DstPort		      2
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  286
-	  SrcBlock		  "P"
-	  SrcPort		  1
-	  DstBlock		  "ESC System"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  416
-	  SrcBlock		  "Gravity\n\n"
-	  SrcPort		  1
-	  Points		  [86, 0]
-	  Branch {
-	    ZOrder		    410
-	    Points		    [0, -70]
-	    DstBlock		    "Scope7"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    409
-	    DstBlock		    "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  415
-	  SrcBlock		  "Integrator"
-	  SrcPort		  1
-	  Points		  [58, 0]
-	  Branch {
-	    ZOrder		    290
-	    Points		    [0, 210; -473, 0; 0, -105]
-	    DstBlock		    "Motor System"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    292
-	    DstBlock		    "Rotor System\n\n\n\n\n\n\n\n"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    291
-	    Points		    [0, -110]
-	    DstBlock		    "Scope2"
-	    DstPort		    1
-	  }
-	}
-      }
-    }
-    Block {
-      BlockType		      SubSystem
-      Name		      "Communication System"
-      SID		      "582"
-      Ports		      [0, 1]
-      Position		      [515, 432, 570, 478]
-      ZOrder		      70
-      RequestExecContextInheritance off
-      Variant		      off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		50
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('output', 1, 'Setpoints', 'texmode', 'on');"
-      }
-      System {
-	Name			"Communication System"
-	Location		[-8, -8, 1928, 1048]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"175"
-	Block {
-	  BlockType		  Step
-	  Name			  "Step"
-	  SID			  "583"
-	  Position		  [925, 390, 955, 420]
-	  ZOrder		  32
-	  Before		  "[0; 0; 0; 0]"
-	  After			  "[0; 0; 0; 0]"
-	  SampleTime		  "Tq"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "setpoints"
-	  SID			  "584"
-	  Position		  [1050, 398, 1080, 412]
-	  ZOrder		  6
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "Step"
-	  SrcPort		  1
-	  DstBlock		  "setpoints"
-	  DstPort		  1
-	}
-      }
-    }
-    Block {
-      BlockType		      SubSystem
-      Name		      "Control System"
-      SID		      "573"
-      Ports		      [4, 1]
-      Position		      [645, 423, 900, 652]
-      ZOrder		      69
-      ShowName		      off
-      RequestExecContextInheritance off
-      Variant		      off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		51
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('input', 1, 'Setpoints', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{filtered}', 'texmo"
-	"de', 'on');\nport_label('input', 3, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmo"
-	"de', 'on');\nport_label('output', 1, 'P', 'texmode', 'on');\ndisp('Control System', 'texmode', 'on');"
-      }
-      System {
-	Name			"Control System"
-	Location		[-8, -8, 1928, 1048]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"80"
-	Block {
-	  BlockType		  Inport
-	  Name			  "setpoints"
-	  SID			  "574"
-	  Position		  [215, 363, 245, 377]
-	  ZOrder		  2
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "euler_angles_filtered"
-	  SID			  "575"
-	  Position		  [215, 523, 245, 537]
-	  ZOrder		  9
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "euler_rates"
-	  SID			  "576"
-	  Position		  [215, 598, 245, 612]
-	  ZOrder		  11
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "current_position"
-	  SID			  "577"
-	  Position		  [215, 448, 245, 462]
-	  ZOrder		  -1
-	  Port			  "4"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "Constant"
-	  SID			  "919"
-	  Position		  [275, 1020, 305, 1050]
-	  ZOrder		  66
-	  Value			  "Tc"
-	  SampleTime		  "Tc"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Controller"
-	  SID			  "604"
-	  Ports			  [13, 4]
-	  Position		  [395, 315, 530, 645]
-	  ZOrder		  31
-	  RequestExecContextInheritance	off
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    52
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se"
-	    "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', "
-	    "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'"
-	    ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\"
-	    "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't"
-	    "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '"
-	    "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode"
-	    "', 'on');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\npo"
-	    "rt_label('output', 4, 'u_R', 'texmode', 'on');\ndisp('Controller', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Controller"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "300"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "x_setpoint"
-	      SID		      "605"
-	      Position		      [475, -217, 505, -203]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "y_setpoint"
-	      SID		      "607"
-	      Position		      [475, -477, 505, -463]
-	      ZOrder		      45
-	      ForegroundColor	      "gray"
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "z_setpoint"
-	      SID		      "608"
-	      Position		      [475, -717, 505, -703]
-	      ZOrder		      46
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw_setpoint"
-	      SID		      "632"
-	      Position		      [475, 53, 505, 67]
-	      ZOrder		      103
-	      ForegroundColor	      "gray"
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "x_position"
-	      SID		      "622"
-	      Position		      [545, -172, 575, -158]
-	      ZOrder		      60
-	      Port		      "5"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "y_position"
-	      SID		      "623"
-	      Position		      [540, -432, 570, -418]
-	      ZOrder		      61
-	      Port		      "6"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "z_position"
-	      SID		      "624"
-	      Position		      [555, -662, 585, -648]
-	      ZOrder		      62
-	      Port		      "7"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "roll"
-	      SID		      "630"
-	      Position		      [835, -432, 865, -418]
-	      ZOrder		      68
-	      Port		      "8"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "pitch"
-	      SID		      "631"
-	      Position		      [840, -172, 870, -158]
-	      ZOrder		      69
-	      Port		      "9"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw"
-	      SID		      "649"
-	      Position		      [560, 98, 590, 112]
-	      ZOrder		      105
-	      Port		      "10"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "roll_rate"
-	      SID		      "633"
-	      Position		      [1095, -432, 1125, -418]
-	      ZOrder		      71
-	      Port		      "11"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "pitch_rate"
-	      SID		      "634"
-	      Position		      [1090, -172, 1120, -158]
-	      ZOrder		      72
-	      Port		      "12"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw_rate"
-	      SID		      "635"
-	      Position		      [820, 118, 850, 132]
-	      ZOrder		      73
-	      Port		      "13"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Altitude Controller Input"
-	      SID		      "1177"
-	      Ports		      [1, 1]
-	      Position		      [685, -727, 750, -693]
-	      ZOrder		      292
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		53
-		$ClassName		"Simulink.Mask"
-		Display			"disp('^Ez_{y,error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Altitude Controller Input"
-		Location		[-7, -7, 1288, 688]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"200"
-		Block {
-		  BlockType		  Inport
-		  Name			  "z_error_model"
-		  SID			  "1250"
-		  Position		  [85, 123, 115, 137]
-		  ZOrder		  290
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1251"
-		  Ports			  [1, 1]
-		  Position		  [215, 151, 285, 189]
-		  ZOrder		  289
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    54
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-7, -7, 1288, 688]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "z_error_model"
-		    SID			    "1252"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "z_error"
-		    SID			    "1253"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "z_error_model"
-		    SrcPort		    1
-		    DstBlock		    "z_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "z error"
-		  SID			  "1090"
-		  Ports			  [0, 1]
-		  Position		  [215, 78, 285, 112]
-		  ZOrder		  280
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    55
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('^Er_{z,error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "z error"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "200"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace6"
-		    SID			    "999"
-		    Position		    [15, 18, 80, 42]
-		    ZOrder		    221
-		    VariableName	    "z_error"
-		    SampleTime		    "Tc"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "z_error"
-		    SID			    "1093"
-		    Position		    [145, 23, 175, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace6"
-		    SrcPort		    1
-		    DstBlock		    "z_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "z_error"
-		  SID			  "1184"
-		  Position		  [400, 123, 430, 137]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1186"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain"
-	      SID		      "880"
-	      Position		      [935, -135, 965, -105]
-	      ZOrder		      149
-	      Gain		      "180/pi"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain1"
-	      SID		      "1021"
-	      Position		      [930, 135, 960, 165]
-	      ZOrder		      242
-	      Gain		      "180/pi"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain2"
-	      SID		      "980"
-	      Position		      [935, -395, 965, -365]
-	      ZOrder		      202
-	      Gain		      "180/pi"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Latitude Controller Input"
-	      SID		      "1127"
-	      Ports		      [1, 1]
-	      Position		      [675, -227, 740, -193]
-	      ZOrder		      287
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		56
-		$ClassName		"Simulink.Mask"
-		Display			"disp('^Er_{x,error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Latitude Controller Input"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "x_error_model"
-		  SID			  "1226"
-		  Position		  [85, 158, 115, 172]
-		  ZOrder		  286
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1227"
-		  Ports			  [1, 1]
-		  Position		  [185, 146, 255, 184]
-		  ZOrder		  285
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    57
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-7, -7, 1288, 688]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "x_error_model"
-		    SID			    "1228"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "x_error"
-		    SID			    "1229"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "x_error_model"
-		    SrcPort		    1
-		    DstBlock		    "x_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "x error"
-		  SID			  "1059"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  278
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    58
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('^Er_{x,error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "x error"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "300"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace"
-		    SID			    "947"
-		    Position		    [20, 18, 85, 42]
-		    ZOrder		    171
-		    VariableName	    "x_error"
-		    SampleTime		    "Tc"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "x_error"
-		    SID			    "1060"
-		    Position		    [230, 23, 260, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace"
-		    SrcPort		    1
-		    DstBlock		    "x_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "x_error"
-		  SID			  "1134"
-		  Position		  [405, 128, 435, 142]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1136"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Longitude Controller Input"
-	      SID		      "1147"
-	      Ports		      [1, 1]
-	      Position		      [670, -487, 735, -453]
-	      ZOrder		      289
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		59
-		$ClassName		"Simulink.Mask"
-		Display			"disp('^Er_{y,error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Longitude Controller Input"
-		Location		[-7, -7, 1288, 688]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "y_error_model"
-		  SID			  "1238"
-		  Position		  [85, 173, 115, 187]
-		  ZOrder		  288
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1239"
-		  Ports			  [1, 1]
-		  Position		  [185, 161, 255, 199]
-		  ZOrder		  287
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    60
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "y_error_model"
-		    SID			    "1240"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "y_error"
-		    SID			    "1241"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "y_error_model"
-		    SrcPort		    1
-		    DstBlock		    "y_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "y error"
-		  SID			  "1078"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  279
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    61
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('^Er_{y,error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "y error"
-		    Location		    [-7, -7, 1288, 688]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "200"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace3"
-		    SID			    "977"
-		    Position		    [15, 18, 80, 42]
-		    ZOrder		    207
-		    VariableName	    "y_error"
-		    SampleTime		    "Tc"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "y_error"
-		    SID			    "1081"
-		    Position		    [145, 23, 175, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace3"
-		    SrcPort		    1
-		    DstBlock		    "y_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "y_error"
-		  SID			  "1154"
-		  Position		  [385, 123, 415, 137]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1156"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller1"
-	      SID		      "1355"
-	      Ports		      [1, 1]
-	      Position		      [1045, 41, 1085, 79]
-	      ZOrder		      313
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "P"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tq"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "29700"
-	      I			      "-77.7"
-	      D			      "2.32"
-	      N			      "1/0.0818"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      off
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller11"
-	      SID		      "1370"
-	      Ports		      [1, 1]
-	      Position		      [790, -229, 830, -191]
-	      ZOrder		      321
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PID"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tc"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "-0.015"
-	      I			      "0"
-	      D			      "-0.25"
-	      N			      "3"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller17"
-	      SID		      "1352"
-	      Ports		      [1, 1]
-	      Position		      [790, -728, 830, -692]
-	      ZOrder		      310
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PID"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tc"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "9804"
-	      I			      "817"
-	      D			      "7353"
-	      N			      "5.79502261645411"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller2"
-	      SID		      "1424"
-	      Ports		      [1, 1]
-	      Position		      [1045, -488, 1085, -452]
-	      ZOrder		      326
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tq"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "15"
-	      I			      "35.1207902652377"
-	      D			      "0.2"
-	      N			      "40.0107970227961"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller3"
-	      SID		      "1423"
-	      Ports		      [1, 1]
-	      Position		      [1295, -488, 1335, -452]
-	      ZOrder		      325
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tq"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "4600"
-	      I			      "1575.82088970639"
-	      D			      "550"
-	      N			      "244.660686071579"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller4"
-	      SID		      "1354"
-	      Ports		      [1, 1]
-	      Position		      [790, 42, 830, 78]
-	      ZOrder		      312
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tc"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "2.6"
-	      I			      "2.36803176515497"
-	      D			      "0"
-	      N			      "3.83298618768959"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller5"
-	      SID		      "1368"
-	      Ports		      [1, 1]
-	      Position		      [1045, -228, 1085, -192]
-	      ZOrder		      319
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tq"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "15"
-	      I			      "35.1207902652377"
-	      D			      "0.2"
-	      N			      "40.0107970227961"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller7"
-	      SID		      "1365"
-	      Ports		      [1, 1]
-	      Position		      [790, -488, 830, -452]
-	      ZOrder		      316
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PID"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tc"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "0.015"
-	      I			      "0"
-	      D			      "0.25"
-	      N			      "3"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller9"
-	      SID		      "1367"
-	      Ports		      [1, 1]
-	      Position		      [1295, -228, 1335, -192]
-	      ZOrder		      318
-	      LibraryVersion	      "1.388"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "Tq"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "4600"
-	      I			      "1575.82088970639"
-	      D			      "550"
-	      N			      "244.660686071579"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Pitch Controller Input"
-	      SID		      "1103"
-	      Ports		      [1, 1]
-	      Position		      [940, -227, 1005, -193]
-	      ZOrder		      283
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		62
-		$ClassName		"Simulink.Mask"
-		Display			"disp('\\theta_{error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Pitch Controller Input"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "pitch_error_model"
-		  SID			  "1230"
-		  Position		  [85, 168, 115, 182]
-		  ZOrder		  286
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1231"
-		  Ports			  [1, 1]
-		  Position		  [185, 156, 255, 194]
-		  ZOrder		  285
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    63
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "pitch_error_model"
-		    SID			    "1232"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "pitch_error"
-		    SID			    "1233"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "pitch_error_model"
-		    SrcPort		    1
-		    DstBlock		    "pitch_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "pitch error"
-		  SID			  "1066"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  274
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    64
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('\\theta_{error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "pitch error"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace"
-		    SID			    "1068"
-		    Position		    [20, 18, 85, 42]
-		    ZOrder		    171
-		    VariableName	    "pitch_error"
-		    SampleTime		    "Tq"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "pitch_error"
-		    SID			    "1069"
-		    Position		    [145, 23, 175, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace"
-		    SrcPort		    1
-		    DstBlock		    "pitch_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "pitch_error"
-		  SID			  "1105"
-		  Position		  [410, 123, 440, 137]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1106"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Pitch Rate Controller Input"
-	      SID		      "1137"
-	      Ports		      [1, 1]
-	      Position		      [1185, -227, 1250, -193]
-	      ZOrder		      288
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		65
-		$ClassName		"Simulink.Mask"
-		Display			"disp('d\\theta/dt_{error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Pitch Rate Controller Input"
-		Location		[-7, -7, 1288, 688]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "pitchrate_error_model"
-		  SID			  "1234"
-		  Position		  [85, 183, 115, 197]
-		  ZOrder		  286
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1235"
-		  Ports			  [1, 1]
-		  Position		  [185, 171, 255, 209]
-		  ZOrder		  285
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    66
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "pitchrate_error_model"
-		    SID			    "1236"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "pitchrate_error"
-		    SID			    "1237"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "pitchrate_error_model"
-		    SrcPort		    1
-		    DstBlock		    "pitchrate_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "pitchrate error"
-		  SID			  "1074"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  278
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    67
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('d\\theta/dt_{error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "pitchrate error"
-		    Location		    [-7, -7, 1288, 688]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace2"
-		    SID			    "950"
-		    Position		    [10, 18, 80, 42]
-		    ZOrder		    175
-		    VariableName	    "pitchrate_error"
-		    SampleTime		    "Tq"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "pitchrate_error"
-		    SID			    "1077"
-		    Position		    [145, 23, 175, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace2"
-		    SrcPort		    1
-		    DstBlock		    "pitchrate_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "pitchrate_error"
-		  SID			  "1144"
-		  Position		  [410, 133, 440, 147]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1146"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Roll Controller Input"
-	      SID		      "1157"
-	      Ports		      [1, 1]
-	      Position		      [950, -487, 1015, -453]
-	      ZOrder		      290
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		68
-		$ClassName		"Simulink.Mask"
-		Display			"disp('\\phi_{error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Roll Controller Input"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "roll_error_model"
-		  SID			  "1242"
-		  Position		  [85, 158, 115, 172]
-		  ZOrder		  288
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1243"
-		  Ports			  [1, 1]
-		  Position		  [185, 146, 255, 184]
-		  ZOrder		  287
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    69
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "roll_error_model"
-		    SID			    "1244"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "roll_error"
-		    SID			    "1245"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "roll_error_model"
-		    SrcPort		    1
-		    DstBlock		    "roll_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "roll error"
-		  SID			  "1082"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  278
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    70
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('\\phi_{error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "roll error"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace4"
-		    SID			    "978"
-		    Position		    [190, 88, 255, 112]
-		    ZOrder		    209
-		    ForegroundColor	    "green"
-		    VariableName	    "roll_error"
-		    SampleTime		    "Tq"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "roll_error"
-		    SID			    "1085"
-		    Position		    [315, 93, 345, 107]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace4"
-		    SrcPort		    1
-		    DstBlock		    "roll_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "roll_error"
-		  SID			  "1164"
-		  Position		  [410, 118, 440, 132]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1166"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Roll Rate Controller Input"
-	      SID		      "1167"
-	      Ports		      [1, 1]
-	      Position		      [1200, -487, 1265, -453]
-	      ZOrder		      291
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		71
-		$ClassName		"Simulink.Mask"
-		Display			"disp('d\\phi/dt_{error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Roll Rate Controller Input"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"175"
-		Block {
-		  BlockType		  Inport
-		  Name			  "rollrate_error_model"
-		  SID			  "1246"
-		  Position		  [85, 163, 115, 177]
-		  ZOrder		  288
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1247"
-		  Ports			  [1, 1]
-		  Position		  [185, 151, 255, 189]
-		  ZOrder		  287
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    72
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "rollrate_error_model"
-		    SID			    "1248"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "rollrate_error"
-		    SID			    "1249"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "rollrate_error_model"
-		    SrcPort		    1
-		    DstBlock		    "rollrate_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "rollrate error"
-		  SID			  "1086"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  279
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    73
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('d\\phi/dt_{error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "rollrate error"
-		    Location		    [-7, -7, 1288, 688]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace5"
-		    SID			    "979"
-		    Position		    [10, 18, 80, 42]
-		    ZOrder		    210
-		    VariableName	    "rollrate_error"
-		    SampleTime		    "Tq"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "rollrate_error"
-		    SID			    "1089"
-		    Position		    [145, 23, 175, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace5"
-		    SrcPort		    1
-		    DstBlock		    "rollrate_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "rollrate_error"
-		  SID			  "1174"
-		  Position		  [405, 128, 435, 142]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1176"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Saturate
-	      Name		      "Saturation"
-	      SID		      "932"
-	      Ports		      [1, 1]
-	      Position		      [1380, 45, 1410, 75]
-	      ZOrder		      161
-	      InputPortMap	      "u0"
-	      UpperLimit	      "20000"
-	      LowerLimit	      "-20000"
-	    }
-	    Block {
-	      BlockType		      Saturate
-	      Name		      "Saturation1"
-	      SID		      "1001"
-	      Ports		      [1, 1]
-	      Position		      [1390, -225, 1420, -195]
-	      ZOrder		      222
-	      InputPortMap	      "u0"
-	      UpperLimit	      "20000"
-	      LowerLimit	      "-20000"
-	    }
-	    Block {
-	      BlockType		      Saturate
-	      Name		      "Saturation2"
-	      SID		      "1002"
-	      Ports		      [1, 1]
-	      Position		      [1390, -485, 1420, -455]
-	      ZOrder		      223
-	      InputPortMap	      "u0"
-	      UpperLimit	      "20000"
-	      LowerLimit	      "-20000"
-	    }
-	    Block {
-	      BlockType		      Saturate
-	      Name		      "Saturation3"
-	      SID		      "1003"
-	      Ports		      [1, 1]
-	      Position		      [1390, -725, 1420, -695]
-	      ZOrder		      224
-	      InputPortMap	      "u0"
-	      UpperLimit	      "20000"
-	      LowerLimit	      "-20000"
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope1"
-	      SID		      "1022"
-	      Ports		      [1]
-	      Position		      [990, 134, 1020, 166]
-	      ZOrder		      241
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData5
-	      YMin		      -237.62576
-	      YMax		      9.97394
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [680 330 1240 750]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope11"
-	      SID		      "984"
-	      Ports		      [1]
-	      Position		      [1215, -386, 1245, -354]
-	      ZOrder		      199
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      on
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData2
-	      YMin		      -1.23139
-	      YMax		      0.20473
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      Array
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [1 76 1909 1039]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope12"
-	      SID		      "985"
-	      Ports		      [1]
-	      Position		      [645, -336, 675, -304]
-	      ZOrder		      200
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData3
-	      YMin		      -5094.66345
-	      YMax		      568.26972
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [1 76 1921 1039]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope13"
-	      SID		      "986"
-	      Ports		      [1]
-	      Position		      [995, -396, 1025, -364]
-	      ZOrder		      201
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      on
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData4
-	      YMin		      -10
-	      YMax		      10
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      Array
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [680 330 1240 750]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope2"
-	      SID		      "795"
-	      Ports		      [1]
-	      Position		      [665, -591, 695, -559]
-	      ZOrder		      107
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData5
-	      YMin		      -233.85726
-	      YMax		      2104.70554
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [1 76 1921 1039]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope3"
-	      SID		      "1006"
-	      Ports		      [1]
-	      Position		      [655, 199, 685, 231]
-	      ZOrder		      226
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData1
-	      YMin		      -171.38344
-	      YMax		      42.10594
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [1 76 1921 1039]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope4"
-	      SID		      "1030"
-	      Ports		      [1]
-	      Position		      [650, -76, 680, -44]
-	      ZOrder		      250
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      on
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData1
-	      YMin		      -227.57395
-	      YMax		      29.15339
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      Array
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [1 76 1921 1039]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope6"
-	      SID		      "825"
-	      Ports		      [1]
-	      Position		      [1205, -126, 1235, -94]
-	      ZOrder		      117
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData1
-	      YMin		      -32.40215
-	      YMax		      23.21935
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [1 76 1921 1039]
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope9"
-	      SID		      "878"
-	      Ports		      [1]
-	      Position		      [995, -136, 1025, -104]
-	      ZOrder		      147
-	      NumInputPorts	      "1"
-	      Open		      off
-	      TimeRange		      auto
-	      TickLabels	      OneTimeTick
-	      ShowLegends	      off
-	      LimitDataPoints	      off
-	      MaxDataPoints	      5000
-	      SaveToWorkspace	      off
-	      SaveName		      ScopeData1
-	      YMin		      -0.5042
-	      YMax		      4.53783
-	      SampleInput	      off
-	      SampleTime	      -1
-	      ZoomMode		      on
-	      Grid		      on
-	      DataFormat	      StructureWithTime
-	      Decimation	      1
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      Location		      [1 76 1921 1039]
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum1"
-	      SID		      "1007"
-	      Ports		      [2, 1]
-	      Position		      [610, 50, 630, 70]
-	      ZOrder		      225
-	      ForegroundColor	      "green"
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum10"
-	      SID		      "988"
-	      Ports		      [2, 1]
-	      Position		      [1140, -480, 1160, -460]
-	      ZOrder		      193
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum11"
-	      SID		      "989"
-	      Ports		      [2, 1]
-	      Position		      [610, -480, 630, -460]
-	      ZOrder		      194
-	      ForegroundColor	      "green"
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum2"
-	      SID		      "1023"
-	      Ports		      [2, 1]
-	      Position		      [870, 50, 890, 70]
-	      ZOrder		      240
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum3"
-	      SID		      "602"
-	      Ports		      [2, 1]
-	      Position		      [875, -220, 895, -200]
-	      ZOrder		      43
-	      ForegroundColor	      "green"
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum4"
-	      SID		      "603"
-	      Ports		      [2, 1]
-	      Position		      [1130, -220, 1150, -200]
-	      ZOrder		      44
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum5"
-	      SID		      "618"
-	      Ports		      [2, 1]
-	      Position		      [610, -220, 630, -200]
-	      ZOrder		      56
-	      ForegroundColor	      "green"
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum7"
-	      SID		      "620"
-	      Ports		      [2, 1]
-	      Position		      [610, -720, 630, -700]
-	      ZOrder		      58
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum9"
-	      SID		      "987"
-	      Ports		      [2, 1]
-	      Position		      [875, -480, 895, -460]
-	      ZOrder		      192
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace"
-	      SID		      "948"
-	      Ports		      [1]
-	      Position		      [875, -290, 985, -260]
-	      ZOrder		      172
-	      ShowName		      off
-	      VariableName	      "pitch_setpoint_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "-1"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace1"
-	      SID		      "951"
-	      Ports		      [1]
-	      Position		      [1125, -290, 1250, -260]
-	      ZOrder		      175
-	      ShowName		      off
-	      VariableName	      "pitchrate_setpoint_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace10"
-	      SID		      "1029"
-	      Ports		      [1]
-	      Position		      [650, 135, 770, 165]
-	      ZOrder		      249
-	      VariableName	      "yaw_value_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace11"
-	      SID		      "1032"
-	      Ports		      [1]
-	      Position		      [645, -390, 765, -360]
-	      ZOrder		      252
-	      ShowName		      off
-	      VariableName	      "y_position_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace12"
-	      SID		      "1033"
-	      Ports		      [1]
-	      Position		      [660, -640, 780, -610]
-	      ZOrder		      253
-	      ShowName		      off
-	      VariableName	      "z_position_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace2"
-	      SID		      "952"
-	      Ports		      [1]
-	      Position		      [1495, -290, 1605, -260]
-	      ZOrder		      176
-	      VariableName	      "x_command_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace3"
-	      SID		      "993"
-	      Ports		      [1]
-	      Position		      [895, -545, 1005, -515]
-	      ZOrder		      207
-	      ShowName		      off
-	      VariableName	      "roll_setpoint_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace4"
-	      SID		      "994"
-	      Ports		      [1]
-	      Position		      [1150, -545, 1275, -515]
-	      ZOrder		      210
-	      ShowName		      off
-	      VariableName	      "rollrate_setpoint_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace5"
-	      SID		      "995"
-	      Ports		      [1]
-	      Position		      [1500, -545, 1610, -515]
-	      ZOrder		      211
-	      ForegroundColor	      "red"
-	      VariableName	      "y_command_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace6"
-	      SID		      "1000"
-	      Ports		      [1]
-	      Position		      [1420, -805, 1530, -775]
-	      ZOrder		      327
-	      VariableName	      "z_command_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace7"
-	      SID		      "1025"
-	      Ports		      [1]
-	      Position		      [870, -20, 990, 10]
-	      ZOrder		      243
-	      ShowName		      off
-	      VariableName	      "yawrate_setpoint_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace8"
-	      SID		      "1026"
-	      Ports		      [1]
-	      Position		      [1495, -20, 1605, 10]
-	      ZOrder		      247
-	      ShowName		      off
-	      VariableName	      "yaw_command_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tq"
-	    }
-	    Block {
-	      BlockType		      ToWorkspace
-	      Name		      "To Workspace9"
-	      SID		      "1028"
-	      Ports		      [1]
-	      Position		      [650, -135, 770, -105]
-	      ZOrder		      248
-	      ShowName		      off
-	      VariableName	      "x_position_model"
-	      MaxDataPoints	      "inf"
-	      SaveFormat	      "Structure With Time"
-	      Save2DSignal	      "3-D array (concatenate along third dimension)"
-	      FixptAsFi		      on
-	      SampleTime	      "Tc"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Yaw Controller Input"
-	      SID		      "1187"
-	      Ports		      [1, 1]
-	      Position		      [675, 43, 740, 77]
-	      ZOrder		      293
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		74
-		$ClassName		"Simulink.Mask"
-		Display			"disp('\\psi_{error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Yaw Controller Input"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"200"
-		Block {
-		  BlockType		  Inport
-		  Name			  "yaw_error_model"
-		  SID			  "1216"
-		  Position		  [50, 158, 80, 172]
-		  ZOrder		  282
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1188"
-		  Ports			  [1, 1]
-		  Position		  [185, 146, 255, 184]
-		  ZOrder		  276
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    75
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "yaw_error_model"
-		    SID			    "1215"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "yaw_error"
-		    SID			    "1190"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    2
-		    SrcBlock		    "yaw_error_model"
-		    SrcPort		    1
-		    DstBlock		    "yaw_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "yaw error"
-		  SID			  "1094"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  281
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    76
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('\\psi_{error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "yaw error"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace7"
-		    SID			    "1005"
-		    Position		    [20, 18, 85, 42]
-		    ZOrder		    228
-		    VariableName	    "yaw_error"
-		    SampleTime		    "Tc"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "yaw_error"
-		    SID			    "1097"
-		    Position		    [145, 23, 175, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace7"
-		    SrcPort		    1
-		    DstBlock		    "yaw_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "yaw_error"
-		  SID			  "1194"
-		  Position		  [410, 123, 440, 137]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1196"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Yaw Rate Controller Input"
-	      SID		      "1197"
-	      Ports		      [1, 1]
-	      Position		      [940, 43, 1005, 77]
-	      ZOrder		      294
-	      ForegroundColor	      "magenta"
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      on
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		77
-		$ClassName		"Simulink.Mask"
-		Display			"disp('d\\psi/dt_{error}', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Yaw Rate Controller Input"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "yawrate_error_model"
-		  SID			  "1225"
-		  Position		  [85, 158, 115, 172]
-		  ZOrder		  284
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "Feedback"
-		  SID			  "1222"
-		  Ports			  [1, 1]
-		  Position		  [185, 146, 255, 184]
-		  ZOrder		  283
-		  ShowName		  off
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==0"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    78
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('Feedback', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "Feedback"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "100"
-		    Block {
-		    BlockType		    Inport
-		    Name		    "yawrate_error_model"
-		    SID			    "1223"
-		    Position		    [105, 103, 135, 117]
-		    ZOrder		    2
-		    IconDisplay		    "Port number"
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "yawrate_error"
-		    SID			    "1224"
-		    Position		    [360, 103, 390, 117]
-		    ZOrder		    -2
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "yawrate_error_model"
-		    SrcPort		    1
-		    DstBlock		    "yawrate_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  SubSystem
-		  Name			  "yawrate error"
-		  SID			  "1098"
-		  Ports			  [0, 1]
-		  Position		  [185, 73, 255, 107]
-		  ZOrder		  282
-		  RequestExecContextInheritance	off
-		  Variant		  off
-		  VariantControl	  "logAnalysisToggle==1"
-		  Object {
-		    $PropName		    "MaskObject"
-		    $ObjectID		    79
-		    $ClassName		    "Simulink.Mask"
-		    Display		    "disp('d\\psi/dt_{error}', 'texmode', 'on');"
-		  }
-		  System {
-		    Name		    "yawrate error"
-		    Location		    [-8, -8, 1928, 1048]
-		    Open		    off
-		    ModelBrowserVisibility  off
-		    ModelBrowserWidth	    200
-		    ScreenColor		    "white"
-		    PaperOrientation	    "landscape"
-		    PaperPositionMode	    "auto"
-		    PaperType		    "usletter"
-		    PaperUnits		    "inches"
-		    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-		    TiledPageScale	    1
-		    ShowPageBoundaries	    off
-		    ZoomFactor		    "200"
-		    Block {
-		    BlockType		    FromWorkspace
-		    Name		    "From\nWorkspace8"
-		    SID			    "1020"
-		    Position		    [15, 18, 80, 42]
-		    ZOrder		    245
-		    VariableName	    "yawrate_error"
-		    SampleTime		    "Tq"
-		    ZeroCross		    on
-		    }
-		    Block {
-		    BlockType		    Outport
-		    Name		    "yawrate_error"
-		    SID			    "1101"
-		    Position		    [145, 23, 175, 37]
-		    ZOrder		    172
-		    IconDisplay		    "Port number"
-		    }
-		    Line {
-		    ZOrder		    1
-		    SrcBlock		    "From\nWorkspace8"
-		    SrcPort		    1
-		    DstBlock		    "yawrate_error"
-		    DstPort		    1
-		    }
-		  }
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "yawrate_error"
-		  SID			  "1204"
-		  Position		  [410, 83, 440, 97]
-		  ZOrder		  -2
-		  ForegroundColor	  "magenta"
-		  IconDisplay		  "Port number"
-		}
-		Annotation {
-		  SID			  "1206"
-		  Name			  "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm"
-		  "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st"
-		  "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\""
-		  " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h"
-		  "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho"
-		  "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c"
-		  "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\""
-		  "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d"
-		  "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> "
-		  "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi"
-		  "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font"
-		  "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>"
-		  "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden"
-		  "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti"
-		  "ve variant and port name matching.</span></p></body></html>"
-		  Tag			  "VSSAddChoiceText"
-		  Position		  [71, 28, 448, 69]
-		  InternalMargins	  [0, 0, 0, 0]
-		  FixedHeight		  off
-		  FixedWidth		  off
-		  HorizontalAlignment	  "left"
-		  Interpreter		  "rich"
-		  ZOrder		  -1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "height_controlled"
-	      SID		      "606"
-	      Position		      [1500, -717, 1530, -703]
-	      ZOrder		      -2
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "y_controlled"
-	      SID		      "636"
-	      Position		      [1505, -477, 1535, -463]
-	      ZOrder		      74
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "x_controlled"
-	      SID		      "637"
-	      Position		      [1500, -217, 1530, -203]
-	      ZOrder		      75
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "yaw_controlled"
-	      SID		      "638"
-	      Position		      [1495, 53, 1525, 67]
-	      ZOrder		      76
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      48
-	      SrcBlock		      "pitch_rate"
-	      SrcPort		      1
-	      Points		      [15, 0]
-	      Branch {
-		ZOrder			491
-		Points			[0, 55]
-		DstBlock		"Scope6"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			229
-		DstBlock		"Sum4"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      26
-	      SrcBlock		      "z_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum7"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      31
-	      SrcBlock		      "x_position"
-	      SrcPort		      1
-	      Points		      [40, 0]
-	      Branch {
-		ZOrder			839
-		Points			[0, 45]
-		Branch {
-		  ZOrder		  843
-		  Points		  [0, 60]
-		  DstBlock		  "Scope4"
-		  DstPort		  1
-		}
-		Branch {
-		  ZOrder		  842
-		  DstBlock		  "To Workspace9"
-		  DstPort		  1
-		}
-	      }
-	      Branch {
-		ZOrder			237
-		DstBlock		"Sum5"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      1613
-	      SrcBlock		      "PID Controller5"
-	      SrcPort		      1
-	      Points		      [15, 0]
-	      Branch {
-		ZOrder			954
-		DstBlock		"Sum4"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			953
-		Points			[0, -65]
-		DstBlock		"To Workspace1"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      1614
-	      SrcBlock		      "PID Controller11"
-	      SrcPort		      1
-	      Points		      [17, 0]
-	      Branch {
-		ZOrder			956
-		DstBlock		"Sum3"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			955
-		Points			[0, -65]
-		DstBlock		"To Workspace"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      43
-	      SrcBlock		      "pitch"
-	      SrcPort		      1
-	      Points		      [10, 0]
-	      Branch {
-		ZOrder			492
-		Points			[0, 45]
-		DstBlock		"Gain"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			490
-		DstBlock		"Sum3"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      494
-	      SrcBlock		      "Gain"
-	      SrcPort		      1
-	      DstBlock		      "Scope9"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1609
-	      SrcBlock		      "PID Controller1"
-	      SrcPort		      1
-	      Points		      [260, 0]
-	      Branch {
-		ZOrder			1345
-		Points			[0, -65]
-		DstBlock		"To Workspace8"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			1344
-		DstBlock		"Saturation"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      1611
-	      SrcBlock		      "PID Controller9"
-	      SrcPort		      1
-	      Points		      [21, 0]
-	      Branch {
-		ZOrder			1274
-		Points			[0, -65]
-		DstBlock		"To Workspace2"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			1273
-		DstBlock		"Saturation1"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      1615
-	      SrcBlock		      "Latitude Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller11"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      699
-	      SrcBlock		      "x_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum5"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      753
-	      SrcBlock		      "roll_rate"
-	      SrcPort		      1
-	      Points		      [20, 0]
-	      Branch {
-		ZOrder			719
-		Points			[0, 55]
-		DstBlock		"Scope11"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			718
-		DstBlock		"Sum10"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      751
-	      SrcBlock		      "y_position"
-	      SrcPort		      1
-	      Points		      [45, 0]
-	      Branch {
-		ZOrder			722
-		Points			[0, 50]
-		Branch {
-		  ZOrder		  1043
-		  Points		  [0, 55]
-		  DstBlock		  "Scope12"
-		  DstPort		  1
-		}
-		Branch {
-		  ZOrder		  845
-		  DstBlock		  "To Workspace11"
-		  DstPort		  1
-		}
-	      }
-	      Branch {
-		ZOrder			721
-		DstBlock		"Sum11"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      1764
-	      SrcBlock		      "PID Controller2"
-	      SrcPort		      1
-	      Points		      [25, 0]
-	      Branch {
-		ZOrder			1709
-		DstBlock		"Sum10"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			1708
-		Points			[0, -60]
-		DstBlock		"To Workspace4"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      1616
-	      SrcBlock		      "PID Controller7"
-	      SrcPort		      1
-	      Points		      [16, 0]
-	      Branch {
-		ZOrder			1713
-		DstBlock		"Sum9"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			1712
-		Points			[0, -60]
-		DstBlock		"To Workspace3"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      752
-	      SrcBlock		      "roll"
-	      SrcPort		      1
-	      Points		      [15, 0]
-	      Branch {
-		ZOrder			731
-		Points			[0, 45]
-		DstBlock		"Gain2"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			730
-		DstBlock		"Sum9"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      733
-	      SrcBlock		      "Gain2"
-	      SrcPort		      1
-	      DstBlock		      "Scope13"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      750
-	      SrcBlock		      "y_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum11"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1503
-	      SrcBlock		      "PID Controller17"
-	      SrcPort		      1
-	      Points		      [525, 0]
-	      Branch {
-		ZOrder			1767
-		Points			[0, -80]
-		DstBlock		"To Workspace6"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			1766
-		DstBlock		"Saturation3"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      785
-	      SrcBlock		      "yaw"
-	      SrcPort		      1
-	      Points		      [25, 0]
-	      Branch {
-		ZOrder			778
-		Points			[0, 45]
-		Branch {
-		  ZOrder		  1214
-		  Points		  [0, 65]
-		  DstBlock		  "Scope3"
-		  DstPort		  1
-		}
-		Branch {
-		  ZOrder		  841
-		  DstBlock		  "To Workspace10"
-		  DstPort		  1
-		}
-	      }
-	      Branch {
-		ZOrder			777
-		DstBlock		"Sum1"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      784
-	      SrcBlock		      "yaw_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      810
-	      SrcBlock		      "yaw_rate"
-	      SrcPort		      1
-	      Points		      [25, 0]
-	      Branch {
-		ZOrder			822
-		Points			[0, 25]
-		DstBlock		"Gain1"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			821
-		DstBlock		"Sum2"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      806
-	      SrcBlock		      "Gain1"
-	      SrcPort		      1
-	      DstBlock		      "Scope1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1501
-	      SrcBlock		      "PID Controller4"
-	      SrcPort		      1
-	      Points		      [11, 0]
-	      Branch {
-		ZOrder			1591
-		DstBlock		"Sum2"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			1590
-		Points			[0, -65]
-		DstBlock		"To Workspace7"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      34
-	      SrcBlock		      "z_position"
-	      SrcPort		      1
-	      Points		      [30, 0]
-	      Branch {
-		ZOrder			108
-		Points			[0, 30]
-		Branch {
-		  ZOrder		  849
-		  DstBlock		  "To Workspace12"
-		  DstPort		  1
-		}
-		Branch {
-		  ZOrder		  848
-		  Points		  [0, 50]
-		  DstBlock		  "Scope2"
-		  DstPort		  1
-		}
-	      }
-	      Branch {
-		ZOrder			107
-		DstBlock		"Sum7"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      1163
-	      SrcBlock		      "Sum1"
-	      SrcPort		      1
-	      DstBlock		      "Yaw Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1500
-	      SrcBlock		      "Yaw Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller4"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1190
-	      SrcBlock		      "Sum2"
-	      SrcPort		      1
-	      DstBlock		      "Yaw Rate Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1608
-	      SrcBlock		      "Yaw Rate Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1194
-	      SrcBlock		      "Sum5"
-	      SrcPort		      1
-	      DstBlock		      "Latitude Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1195
-	      SrcBlock		      "Sum3"
-	      SrcPort		      1
-	      DstBlock		      "Pitch Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1612
-	      SrcBlock		      "Pitch Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller5"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1197
-	      SrcBlock		      "Sum4"
-	      SrcPort		      1
-	      DstBlock		      "Pitch Rate Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1610
-	      SrcBlock		      "Pitch Rate Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller9"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1199
-	      SrcBlock		      "Sum11"
-	      SrcPort		      1
-	      DstBlock		      "Longitude Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1617
-	      SrcBlock		      "Longitude Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller7"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1201
-	      SrcBlock		      "Sum9"
-	      SrcPort		      1
-	      DstBlock		      "Roll Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1765
-	      SrcBlock		      "Roll Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1204
-	      SrcBlock		      "Sum10"
-	      SrcPort		      1
-	      DstBlock		      "Roll Rate Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1502
-	      SrcBlock		      "Altitude Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller17"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1210
-	      SrcBlock		      "Sum7"
-	      SrcPort		      1
-	      DstBlock		      "Altitude Controller Input"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1763
-	      SrcBlock		      "Roll Rate Controller Input"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1762
-	      SrcBlock		      "PID Controller3"
-	      SrcPort		      1
-	      Points		      [16, 0]
-	      Branch {
-		ZOrder			1602
-		Points			[0, -60]
-		DstBlock		"To Workspace5"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			1601
-		DstBlock		"Saturation2"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      1701
-	      SrcBlock		      "Saturation2"
-	      SrcPort		      1
-	      DstBlock		      "y_controlled"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1716
-	      SrcBlock		      "Saturation1"
-	      SrcPort		      1
-	      DstBlock		      "x_controlled"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      1768
-	      SrcBlock		      "Saturation"
-	      SrcPort		      1
-	      DstBlock		      "yaw_controlled"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Reference
-	  Name			  "Counter\nFree-Running"
-	  SID			  "899"
-	  Ports			  [0, 1]
-	  Position		  [275, 955, 305, 985]
-	  ZOrder		  59
-	  LibraryVersion	  "1.388"
-	  SourceBlock		  "simulink/Sources/Counter\nFree-Running"
-	  SourceType		  "Counter Free-Running"
-	  ContentPreviewEnabled	  off
-	  NumBits		  "32"
-	  tsamp			  "Tc"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux"
-	  SID			  "586"
-	  Ports			  [1, 4]
-	  Position		  [300, 319, 305, 416]
-	  ZOrder		  13
-	  ShowName		  off
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux1"
-	  SID			  "639"
-	  Ports			  [1, 3]
-	  Position		  [300, 494, 305, 566]
-	  ZOrder		  32
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux2"
-	  SID			  "588"
-	  Ports			  [1, 3]
-	  Position		  [285, 419, 290, 491]
-	  ZOrder		  15
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux3"
-	  SID			  "1422"
-	  Ports			  [1, 4]
-	  Position		  [1650, 511, 1655, 549]
-	  ZOrder		  321
-	  ShowName		  off
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux4"
-	  SID			  "640"
-	  Ports			  [1, 3]
-	  Position		  [275, 569, 280, 641]
-	  ZOrder		  33
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "MATLAB Function1"
-	  SID			  "887"
-	  Ports			  [15, 6]
-	  Position		  [390, 687, 530, 1013]
-	  ZOrder		  47
-	  Commented		  "on"
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  SystemSampleTime	  "Tq"
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    80
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se"
-	    "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', "
-	    "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'"
-	    ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\"
-	    "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't"
-	    "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '"
-	    "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('input', 14, 'VRPN ID', 'tex"
-	    "mode', 'on');\nport_label('input', 15, '\\tau_c', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode', 'o"
-	    "n');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\nport_la"
-	    "bel('output', 4, 'u_R', 'texmode', 'on');\nport_label('output', 5, 'PID y out', 'texmode', 'on');\nport_label('ou"
-	    "tput', 6, 'PID roll out', 'texmode', 'on');\ndisp('C Controller', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "MATLAB Function1"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "41"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "set_x"
-	      SID		      "887::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "set_y"
-	      SID		      "887::22"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "set_z"
-	      SID		      "887::23"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      14
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "set_yaw"
-	      SID		      "887::24"
-	      Position		      [20, 206, 40, 224]
-	      ZOrder		      15
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_x"
-	      SID		      "887::25"
-	      Position		      [20, 246, 40, 264]
-	      ZOrder		      16
-	      Port		      "5"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_y"
-	      SID		      "887::26"
-	      Position		      [20, 281, 40, 299]
-	      ZOrder		      17
-	      Port		      "6"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_z"
-	      SID		      "887::27"
-	      Position		      [20, 316, 40, 334]
-	      ZOrder		      18
-	      Port		      "7"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_phi"
-	      SID		      "887::28"
-	      Position		      [20, 351, 40, 369]
-	      ZOrder		      19
-	      Port		      "8"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_theta"
-	      SID		      "887::29"
-	      Position		      [20, 386, 40, 404]
-	      ZOrder		      20
-	      Port		      "9"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_psi"
-	      SID		      "887::30"
-	      Position		      [20, 426, 40, 444]
-	      ZOrder		      21
-	      Port		      "10"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_phi_d"
-	      SID		      "887::31"
-	      Position		      [20, 461, 40, 479]
-	      ZOrder		      22
-	      Port		      "11"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_theta_d"
-	      SID		      "887::32"
-	      Position		      [20, 496, 40, 514]
-	      ZOrder		      23
-	      Port		      "12"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "cur_psi_d"
-	      SID		      "887::33"
-	      Position		      [20, 531, 40, 549]
-	      ZOrder		      24
-	      Port		      "13"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "vrpn_id"
-	      SID		      "887::37"
-	      Position		      [20, 566, 40, 584]
-	      ZOrder		      28
-	      Port		      "14"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Tc"
-	      SID		      "887::41"
-	      Position		      [20, 606, 40, 624]
-	      ZOrder		      31
-	      Port		      "15"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "887::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 350, 320, 390]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "887::19"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 15"
-	      Ports		      [15, 7]
-	      Position		      [180, 110, 230, 430]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[15 7]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"z_corr"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"y_cor"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		4
-		Name			"x_corr"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		5
-		Name			"yaw_corr"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		6
-		Name			"pid_y_out"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		7
-		Name			"pid_roll_out"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "887::21"
-	      Position		      [460, 361, 480, 379]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "z_corr"
-	      SID		      "887::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "y_cor"
-	      SID		      "887::34"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      25
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "x_corr"
-	      SID		      "887::35"
-	      Position		      [460, 171, 480, 189]
-	      ZOrder		      26
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "yaw_corr"
-	      SID		      "887::36"
-	      Position		      [460, 206, 480, 224]
-	      ZOrder		      27
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "pid_y_out"
-	      SID		      "887::38"
-	      Position		      [460, 246, 480, 264]
-	      ZOrder		      29
-	      Port		      "5"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "pid_roll_out"
-	      SID		      "887::39"
-	      Position		      [460, 281, 480, 299]
-	      ZOrder		      30
-	      Port		      "6"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      319
-	      SrcBlock		      "set_x"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      320
-	      SrcBlock		      "set_y"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      321
-	      SrcBlock		      "set_z"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      322
-	      SrcBlock		      "set_yaw"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      4
-	    }
-	    Line {
-	      ZOrder		      323
-	      SrcBlock		      "cur_x"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      5
-	    }
-	    Line {
-	      ZOrder		      324
-	      SrcBlock		      "cur_y"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      6
-	    }
-	    Line {
-	      ZOrder		      325
-	      SrcBlock		      "cur_z"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      7
-	    }
-	    Line {
-	      ZOrder		      326
-	      SrcBlock		      "cur_phi"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      8
-	    }
-	    Line {
-	      ZOrder		      327
-	      SrcBlock		      "cur_theta"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      9
-	    }
-	    Line {
-	      ZOrder		      328
-	      SrcBlock		      "cur_psi"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      10
-	    }
-	    Line {
-	      ZOrder		      329
-	      SrcBlock		      "cur_phi_d"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      11
-	    }
-	    Line {
-	      ZOrder		      330
-	      SrcBlock		      "cur_theta_d"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      12
-	    }
-	    Line {
-	      ZOrder		      331
-	      SrcBlock		      "cur_psi_d"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      13
-	    }
-	    Line {
-	      ZOrder		      332
-	      SrcBlock		      "vrpn_id"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      14
-	    }
-	    Line {
-	      ZOrder		      333
-	      SrcBlock		      "Tc"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      15
-	    }
-	    Line {
-	      Name		      "z_corr"
-	      ZOrder		      334
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "z_corr"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "y_cor"
-	      ZOrder		      335
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "y_cor"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "x_corr"
-	      ZOrder		      336
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      4
-	      DstBlock		      "x_corr"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "yaw_corr"
-	      ZOrder		      337
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      5
-	      DstBlock		      "yaw_corr"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "pid_y_out"
-	      ZOrder		      338
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      6
-	      DstBlock		      "pid_y_out"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "pid_roll_out"
-	      ZOrder		      339
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      7
-	      DstBlock		      "pid_roll_out"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      340
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      341
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Motor Commands"
-	  SID			  "1409"
-	  Ports			  [1, 1]
-	  Position		  [1400, 457, 1555, 503]
-	  ZOrder		  319
-	  ForegroundColor	  "magenta"
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Variant		  on
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    81
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "disp('Motor Commands', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Motor Commands"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "175"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "z_command_model"
-	      SID		      "1410"
-	      Position		      [85, 118, 115, 132]
-	      ZOrder		      288
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Feedback"
-	      SID		      "1411"
-	      Ports		      [1, 1]
-	      Position		      [185, 153, 345, 187]
-	      ZOrder		      287
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==0"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		82
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Motor Command from Model', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Feedback"
-		Location		[-7, -7, 1288, 688]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "z_command_model"
-		  SID			  "1412"
-		  Position		  [105, 103, 135, 117]
-		  ZOrder		  2
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "z_command"
-		  SID			  "1413"
-		  Position		  [360, 103, 390, 117]
-		  ZOrder		  -2
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "z_command_model"
-		  SrcPort		  1
-		  DstBlock		  "z_command"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Motor Command"
-	      SID		      "1414"
-	      Ports		      [0, 1]
-	      Position		      [210, 75, 320, 105]
-	      ZOrder		      279
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==1"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		83
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Motor Command', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Motor Command"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"125"
-		Block {
-		  BlockType		  FromWorkspace
-		  Name			  "From\nWorkspace5"
-		  SID			  "1415"
-		  Position		  [-35, 17, 80, 43]
-		  ZOrder		  210
-		  VariableName		  "motor_commands"
-		  SampleTime		  "Tq"
-		  ZeroCross		  on
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "z_command"
-		  SID			  "1416"
-		  Position		  [145, 23, 175, 37]
-		  ZOrder		  172
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "From\nWorkspace5"
-		  SrcPort		  1
-		  DstBlock		  "z_command"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "z_command"
-	      SID		      "1417"
-	      Position		      [410, 118, 440, 132]
-	      ZOrder		      -2
-	      ForegroundColor	      "magenta"
-	      IconDisplay	      "Port number"
-	    }
-	    Annotation {
-	      SID		      "1418"
-	      Name		      "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">"
-	      "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap"
-	      "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n"
-	      "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde"
-	      "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m"
-	      "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco"
-	      "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;"
-	      "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti"
-	      "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H"
-	      "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b"
-	      "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st"
-	      "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co"
-	      "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin"
-	      "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo"
-	      "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>"
-	      Tag		      "VSSAddChoiceText"
-	      Position		      [71, 28, 448, 69]
-	      InternalMargins	      [0, 0, 0, 0]
-	      FixedHeight	      off
-	      FixedWidth	      off
-	      HorizontalAlignment     "left"
-	      Interpreter	      "rich"
-	      ZOrder		      -1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Saturate
-	  Name			  "Saturation"
-	  SID			  "756"
-	  Ports			  [1, 1]
-	  Position		  [1270, 465, 1300, 495]
-	  ZOrder		  44
-	  InputPortMap		  "u0"
-	  UpperLimit		  "Pmax*ones(4,1)"
-	  LowerLimit		  "Pmin*ones(4,1)"
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope"
-	  SID			  "1421"
-	  Ports			  [4]
-	  Position		  [1705, 514, 1735, 546]
-	  ZOrder		  320
-	  NumInputPorts		  "4"
-	  Open			  off
-	  TimeRange		  auto
-	  TickLabels		  OneTimeTick
-	  ShowLegends		  off
-	  LimitDataPoints	  off
-	  MaxDataPoints		  5000
-	  SaveToWorkspace	  off
-	  SaveName		  ScopeData1
-	  YMin			  127563.375~120690.00000~120652.25~129711.75
-	  YMax			  167209.625~181750.00000~182389.75~170414.25
-	  SampleInput		  off
-	  SampleTime		  -1
-	  ZoomMode		  on
-	  Grid			  on
-	  DataFormat		  StructureWithTime
-	  Decimation		  1
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	    axes4		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  Location		  [962 84 1920 1038]
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Signal Mixer"
-	  SID			  "647"
-	  Ports			  [4, 1]
-	  Position		  [960, 320, 1220, 640]
-	  ZOrder		  35
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ParametersOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Variant		  off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    84
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'u_T', 'texmode', 'on');\nport_label('input', 2, 'u_A', 'texmode', 'on');\np"
-	    "ort_label('input', 3, 'u_E', 'texmode', 'on');\nport_label('input', 4, 'u_R', 'texmode', 'on');\nport_label('outp"
-	    "ut', 1, 'P', 'texmode', 'on');\ndisp('Signal Mixer', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Signal Mixer"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "27"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "height_controlled"
-	      SID		      "647::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "y_controlled"
-	      SID		      "647::23"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      14
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "x_controlled"
-	      SID		      "647::22"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      13
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw_controlled"
-	      SID		      "647::24"
-	      Position		      [20, 206, 40, 224]
-	      ZOrder		      15
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "647::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "647::19"
-	      Tag		      "Stateflow S-Function Quadcopter_Model_R2015_A 14"
-	      Ports		      [4, 2]
-	      Position		      [180, 107, 230, 208]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[4 2]"
-	      SFunctionDeploymentMode off
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"P"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "647::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "P"
-	      SID		      "647::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      105
-	      SrcBlock		      "height_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      106
-	      SrcBlock		      "y_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      107
-	      SrcBlock		      "x_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      108
-	      SrcBlock		      "yaw_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      4
-	    }
-	    Line {
-	      Name		      "P"
-	      ZOrder		      109
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "P"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      110
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      111
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum"
-	  SID			  "748"
-	  Ports			  [2, 1]
-	  Position		  [665, 350, 685, 370]
-	  ZOrder		  36
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum1"
-	  SID			  "749"
-	  Ports			  [2, 1]
-	  Position		  [665, 430, 685, 450]
-	  ZOrder		  37
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum2"
-	  SID			  "750"
-	  Ports			  [2, 1]
-	  Position		  [665, 510, 685, 530]
-	  ZOrder		  38
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum3"
-	  SID			  "751"
-	  Ports			  [2, 1]
-	  Position		  [665, 590, 685, 610]
-	  ZOrder		  39
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Throttle Command Input"
-	  SID			  "1278"
-	  Ports			  [1, 1]
-	  Position		  [740, 337, 895, 383]
-	  ZOrder		  318
-	  ForegroundColor	  "magenta"
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Variant		  on
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    85
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "disp('Throttle Command', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Throttle Command Input"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "175"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "z_command_model"
-	      SID		      "1279"
-	      Position		      [85, 118, 115, 132]
-	      ZOrder		      288
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Feedback"
-	      SID		      "1280"
-	      Ports		      [1, 1]
-	      Position		      [185, 153, 345, 187]
-	      ZOrder		      287
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==0"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		86
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Throttle Command from Model', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Feedback"
-		Location		[-7, -7, 1288, 688]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		Block {
-		  BlockType		  Inport
-		  Name			  "z_command_model"
-		  SID			  "1281"
-		  Position		  [105, 103, 135, 117]
-		  ZOrder		  2
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "z_command"
-		  SID			  "1282"
-		  Position		  [360, 103, 390, 117]
-		  ZOrder		  -2
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "z_command_model"
-		  SrcPort		  1
-		  DstBlock		  "z_command"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "Throttle Command"
-	      SID		      "1283"
-	      Ports		      [0, 1]
-	      Position		      [210, 75, 320, 105]
-	      ZOrder		      279
-	      ShowName		      off
-	      RequestExecContextInheritance off
-	      Variant		      off
-	      VariantControl	      "logAnalysisToggle==1"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		87
-		$ClassName		"Simulink.Mask"
-		Display			"disp('Throttle Command', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"Throttle Command"
-		Location		[-8, -8, 1928, 1048]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"175"
-		Block {
-		  BlockType		  FromWorkspace
-		  Name			  "From\nWorkspace5"
-		  SID			  "1284"
-		  Position		  [-35, 17, 80, 43]
-		  ZOrder		  210
-		  VariableName		  "throttle_command"
-		  SampleTime		  "Tq"
-		  ZeroCross		  on
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "z_command"
-		  SID			  "1285"
-		  Position		  [145, 23, 175, 37]
-		  ZOrder		  172
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "From\nWorkspace5"
-		  SrcPort		  1
-		  DstBlock		  "z_command"
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "z_command"
-	      SID		      "1286"
-	      Position		      [410, 118, 440, 132]
-	      ZOrder		      -2
-	      ForegroundColor	      "magenta"
-	      IconDisplay	      "Port number"
-	    }
-	    Annotation {
-	      SID		      "1287"
-	      Name		      "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">"
-	      "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap"
-	      "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n"
-	      "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde"
-	      "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m"
-	      "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco"
-	      "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;"
-	      "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti"
-	      "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H"
-	      "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b"
-	      "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st"
-	      "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co"
-	      "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin"
-	      "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo"
-	      "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>"
-	      Tag		      "VSSAddChoiceText"
-	      Position		      [71, 28, 448, 69]
-	      InternalMargins	      [0, 0, 0, 0]
-	      FixedHeight	      off
-	      FixedWidth	      off
-	      HorizontalAlignment     "left"
-	      Interpreter	      "rich"
-	      ZOrder		      -1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  ToWorkspace
-	  Name			  "To Workspace3"
-	  SID			  "1207"
-	  Ports			  [1]
-	  Position		  [1445, 380, 1555, 410]
-	  ZOrder		  228
-	  ShowName		  off
-	  VariableName		  "motorCommands"
-	  MaxDataPoints		  "inf"
-	  SaveFormat		  "Structure With Time"
-	  Save2DSignal		  "3-D array (concatenate along third dimension)"
-	  FixptAsFi		  on
-	  SampleTime		  "Tq"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "height_controlled_o"
-	  SID			  "752"
-	  Position		  [615, 380, 645, 410]
-	  ZOrder		  40
-	  Value			  "height_controlled_o"
-	  SampleTime		  "Tc"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "x_controlled_o"
-	  SID			  "754"
-	  Position		  [615, 545, 645, 575]
-	  ZOrder		  42
-	  Value			  "x_controlled_o"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "y_controlled_o"
-	  SID			  "753"
-	  Position		  [615, 465, 645, 495]
-	  ZOrder		  41
-	  Value			  "y_controlled_o"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "yaw_controlled_o"
-	  SID			  "755"
-	  Position		  [615, 630, 645, 660]
-	  ZOrder		  43
-	  Value			  "yaw_controlled_o"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "P"
-	  SID			  "578"
-	  Position		  [1665, 473, 1695, 487]
-	  ZOrder		  -2
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "setpoints"
-	  SrcPort		  1
-	  DstBlock		  "Demux"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  30
-	  SrcBlock		  "euler_angles_filtered"
-	  SrcPort		  1
-	  DstBlock		  "Demux1"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  3
-	  SrcBlock		  "current_position"
-	  SrcPort		  1
-	  DstBlock		  "Demux2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  34
-	  SrcBlock		  "euler_rates"
-	  SrcPort		  1
-	  DstBlock		  "Demux4"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  27
-	  SrcBlock		  "Demux"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  28
-	  SrcBlock		  "Demux"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  29
-	  SrcBlock		  "Demux"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  40
-	  SrcBlock		  "Demux2"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  5
-	}
-	Line {
-	  ZOrder		  41
-	  SrcBlock		  "Demux2"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  6
-	}
-	Line {
-	  ZOrder		  42
-	  SrcBlock		  "Demux2"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  7
-	}
-	Line {
-	  ZOrder		  68
-	  SrcBlock		  "Controller"
-	  SrcPort		  2
-	  DstBlock		  "Sum1"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  72
-	  SrcBlock		  "Controller"
-	  SrcPort		  4
-	  DstBlock		  "Sum3"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  77
-	  SrcBlock		  "y_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum1"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  78
-	  SrcBlock		  "x_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum2"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  79
-	  SrcBlock		  "yaw_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum3"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  80
-	  SrcBlock		  "Signal Mixer"
-	  SrcPort		  1
-	  DstBlock		  "Saturation"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  84
-	  SrcBlock		  "Demux1"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  8
-	}
-	Line {
-	  ZOrder		  86
-	  SrcBlock		  "Demux1"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  9
-	}
-	Line {
-	  ZOrder		  90
-	  SrcBlock		  "Demux4"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  11
-	}
-	Line {
-	  ZOrder		  91
-	  SrcBlock		  "Demux4"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  12
-	}
-	Line {
-	  ZOrder		  93
-	  SrcBlock		  "Demux4"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  13
-	}
-	Line {
-	  ZOrder		  94
-	  SrcBlock		  "Demux"
-	  SrcPort		  4
-	  DstBlock		  "Controller"
-	  DstPort		  4
-	}
-	Line {
-	  ZOrder		  95
-	  SrcBlock		  "Demux1"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  10
-	}
-	Line {
-	  ZOrder		  131
-	  SrcBlock		  "Controller"
-	  SrcPort		  3
-	  DstBlock		  "Sum2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  205
-	  SrcBlock		  "Counter\nFree-Running"
-	  SrcPort		  1
-	  DstBlock		  "MATLAB Function1"
-	  DstPort		  14
-	}
-	Line {
-	  ZOrder		  235
-	  SrcBlock		  "Constant"
-	  SrcPort		  1
-	  Points		  [43, 0; 0, -45]
-	  DstBlock		  "MATLAB Function1"
-	  DstPort		  15
-	}
-	Line {
-	  ZOrder		  501
-	  SrcBlock		  "Sum1"
-	  SrcPort		  1
-	  DstBlock		  "Signal Mixer"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  500
-	  SrcBlock		  "Sum2"
-	  SrcPort		  1
-	  DstBlock		  "Signal Mixer"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  499
-	  SrcBlock		  "Sum3"
-	  SrcPort		  1
-	  DstBlock		  "Signal Mixer"
-	  DstPort		  4
-	}
-	Line {
-	  ZOrder		  495
-	  SrcBlock		  "Throttle Command Input"
-	  SrcPort		  1
-	  DstBlock		  "Signal Mixer"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  519
-	  SrcBlock		  "Controller"
-	  SrcPort		  1
-	  DstBlock		  "Sum"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  520
-	  SrcBlock		  "height_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  521
-	  SrcBlock		  "Motor Commands"
-	  SrcPort		  1
-	  Points		  [42, 0]
-	  Branch {
-	    ZOrder		    540
-	    Points		    [0, 50]
-	    DstBlock		    "Demux3"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    539
-	    DstBlock		    "P"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  535
-	  SrcBlock		  "Demux3"
-	  SrcPort		  1
-	  DstBlock		  "Scope"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  536
-	  SrcBlock		  "Demux3"
-	  SrcPort		  2
-	  DstBlock		  "Scope"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  537
-	  SrcBlock		  "Demux3"
-	  SrcPort		  3
-	  DstBlock		  "Scope"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  538
-	  SrcBlock		  "Demux3"
-	  SrcPort		  4
-	  DstBlock		  "Scope"
-	  DstPort		  4
-	}
-	Line {
-	  ZOrder		  543
-	  SrcBlock		  "Sum"
-	  SrcPort		  1
-	  DstBlock		  "Throttle Command Input"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  206
-	  SrcBlock		  "Saturation"
-	  SrcPort		  1
-	  Points		  [49, 0]
-	  Branch {
-	    ZOrder		    557
-	    Points		    [0, -85]
-	    DstBlock		    "To Workspace3"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    556
-	    DstBlock		    "Motor Commands"
-	    DstPort		    1
-	  }
-	}
-      }
-    }
-    Line {
-      ZOrder		      52
-      SrcBlock		      "Control System"
-      SrcPort		      1
-      DstBlock		      "Actuation"
-      DstPort		      1
-    }
-    Line {
-      ZOrder		      55
-      SrcBlock		      "Communication System"
-      SrcPort		      1
-      DstBlock		      "Control System"
-      DstPort		      1
-    }
-    Line {
-      ZOrder		      189
-      SrcBlock		      "Actuation"
-      SrcPort		      1
-      DstBlock		      "     Sensors   "
-      DstPort		      1
-    }
-    Line {
-      ZOrder		      190
-      SrcBlock		      "Actuation"
-      SrcPort		      2
-      DstBlock		      "     Sensors   "
-      DstPort		      2
-    }
-    Line {
-      ZOrder		      191
-      SrcBlock		      "Actuation"
-      SrcPort		      3
-      DstBlock		      "     Sensors   "
-      DstPort		      3
-    }
-    Line {
-      ZOrder		      192
-      SrcBlock		      "Actuation"
-      SrcPort		      4
-      DstBlock		      "     Sensors   "
-      DstPort		      4
-    }
-    Line {
-      ZOrder		      193
-      SrcBlock		      "Actuation"
-      SrcPort		      5
-      DstBlock		      "     Sensors   "
-      DstPort		      5
-    }
-    Line {
-      ZOrder		      194
-      SrcBlock		      "Actuation"
-      SrcPort		      6
-      DstBlock		      "     Sensors   "
-      DstPort		      6
-    }
-    Line {
-      ZOrder		      222
-      SrcBlock		      "     Sensors   "
-      SrcPort		      3
-      Points		      [15, 0; 0, 56; -909, 0; 0, -56]
-      DstBlock		      "Control System"
-      DstPort		      4
-    }
-    Line {
-      ZOrder		      223
-      SrcBlock		      "     Sensors   "
-      SrcPort		      2
-      Points		      [33, 0; 0, 154; -941, 0; 0, -129]
-      DstBlock		      "Control System"
-      DstPort		      3
-    }
-    Line {
-      ZOrder		      224
-      SrcBlock		      "     Sensors   "
-      SrcPort		      1
-      Points		      [47, 0; 0, 247; -965, 0; 0, -197]
-      DstBlock		      "Control System"
-      DstPort		      2
-    }
-  }
-}
-#Finite State Machines
-#
-#   Stateflow 80000010
-#
-#
-Stateflow {
-  machine {
-    id			    1
-    name		    "Quadcopter_Model_R2015_A"
-    created		    "03-Nov-2016 18:34:53"
-    isLibrary		    0
-    sfVersion		    80000006
-    firstTarget		    197
-  }
-  chart {
-    id			    2
-    machine		    1
-    name		    "Actuation/Gravity\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 3 0 0]
-    viewObj		    2
-    ssIdHighWaterMark	    7
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    1
-    disableImplicitCasting  1
-    eml {
-      name		      "gravity"
-    }
-    firstData		    4
-    firstTransition	    8
-    firstJunction	    7
-  }
-  state {
-    id			    3
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    2
-    treeNode		    [2 0 0 0]
-    superState		    SUBCHART
-    subviewer		    2
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function E_Fg = gravity(m, g)\n\nE_Fg = [0; 0; m*g];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    4
-    ssIdNumber		    5
-    name		    "E_Fg"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [2 0 5]
-  }
-  data {
-    id			    5
-    ssIdNumber		    6
-    name		    "m"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [2 4 6]
-  }
-  data {
-    id			    6
-    ssIdNumber		    7
-    name		    "g"
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [2 5 0]
-  }
-  junction {
-    id			    7
-    position		    [23.5747 49.5747 7]
-    chart		    2
-    subviewer		    2
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [2 0 0]
-  }
-  transition {
-    id			    8
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      7
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    2
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    2
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [2 0 0]
-  }
-  instance {
-    id			    9
-    machine		    1
-    name		    "Actuation/Gravity\n\n"
-    chart		    2
-  }
-  chart {
-    id			    10
-    machine		    1
-    name		    "Actuation/Lbe\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 11 0 0]
-    viewObj		    10
-    ssIdHighWaterMark	    11
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    2
-    disableImplicitCasting  1
-    eml {
-      name		      "linear_body_earth_conversion"
-    }
-    firstData		    12
-    firstTransition	    16
-    firstJunction	    15
-  }
-  state {
-    id			    11
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    10
-    treeNode		    [10 0 0 0]
-    superState		    SUBCHART
-    subviewer		    10
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function E_ro  = linear_body_earth_conversion(B_vo, euler_angles)\n\neuler_rates = zeros(3,1);\nE"
-      "_ro = zeros(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLeb = [cos(thet"
-      "a)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ..."
-      "\n       cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(p"
-      "hi)*cos(psi); ...\n           -sin(theta)    ,                sin(phi)*cos(theta)            ,                 c"
-      "os(phi)*cos(theta)           ];\n\nE_ro = Leb * B_vo;"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    12
-    ssIdNumber		    7
-    name		    "B_vo"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [10 0 13]
-  }
-  data {
-    id			    13
-    ssIdNumber		    11
-    name		    "euler_angles"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [10 12 14]
-  }
-  data {
-    id			    14
-    ssIdNumber		    9
-    name		    "E_ro"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [10 13 0]
-  }
-  junction {
-    id			    15
-    position		    [23.5747 49.5747 7]
-    chart		    10
-    subviewer		    10
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [10 0 0]
-  }
-  transition {
-    id			    16
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      15
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    10
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    10
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [10 0 0]
-  }
-  instance {
-    id			    17
-    machine		    1
-    name		    "Actuation/Lbe\n\n\n\n\n\n"
-    chart		    10
-  }
-  chart {
-    id			    18
-    machine		    1
-    name		    "     Sensors   /3D Graphical Simulation1/MATLAB Function"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 19 0 0]
-    viewObj		    18
-    ssIdHighWaterMark	    5
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    3
-    disableImplicitCasting  1
-    eml {
-      name		      "eigenaxis_ucart"
-    }
-    firstData		    20
-    firstTransition	    23
-    firstJunction	    22
-  }
-  state {
-    id			    19
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    18
-    treeNode		    [18 0 0 0]
-    superState		    SUBCHART
-    subviewer		    18
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n    u(1) = 0.0001;\nend\n\nif abs(u(2)"
-      ")< 0.0001\n    u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n    u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) "
-      "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin("
-      "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = "
-      "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u("
-      "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n    \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; "
-      "C31-C13; C12-C21]/(2*sin(theta));\n    \ny = [e; theta];\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    20
-    ssIdNumber		    4
-    name		    "u"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [18 0 21]
-  }
-  data {
-    id			    21
-    ssIdNumber		    5
-    name		    "y"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [18 20 0]
-  }
-  junction {
-    id			    22
-    position		    [23.5747 49.5747 7]
-    chart		    18
-    subviewer		    18
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [18 0 0]
-  }
-  transition {
-    id			    23
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      22
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    18
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    18
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [18 0 0]
-  }
-  instance {
-    id			    24
-    machine		    1
-    name		    "     Sensors   /3D Graphical Simulation1/MATLAB Function"
-    chart		    18
-  }
-  chart {
-    id			    25
-    machine		    1
-    name		    "Actuation/ESC System"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 26 0 0]
-    viewObj		    25
-    ssIdHighWaterMark	    18
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    4
-    disableImplicitCasting  1
-    eml {
-      name		      "ESC"
-    }
-    firstData		    27
-    firstTransition	    33
-    firstJunction	    32
-  }
-  state {
-    id			    26
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    25
-    treeNode		    [25 0 0 0]
-    superState		    SUBCHART
-    subviewer		    25
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function Vb_eff   = ESC(P, Pmin, Pmax, Vb)\n\nP1 = P(1);\nP2 = P(2);\nP3 = P(3);\nP4 = P(4);\n\n%"
-      " Define u_Pi for each of the rotors, limiting it to be greater than 0\n% u_P0 = (rotor_0_duty_cycle/100 - Pmin) "
-      "/ (Pmax - Pmin);\n% u_P1 = (rotor_1_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u_P2 = (rotor_2_duty_cycle/100 - "
-      "Pmin) / (Pmax - Pmin);\n% u_P3 = (rotor_3_duty_cycle/100 - Pmin) / (Pmax - Pmin);\nu_P0 = (P1 - Pmin) / (Pmax - "
-      "Pmin);\nu_P1 = (P2 - Pmin) / (Pmax - Pmin);\nu_P2 = (P3 - Pmin) / (Pmax - Pmin);\nu_P3 = (P4 - Pmin) / (Pmax - P"
-      "min);\n\n\n% Determine the effective battery voltage from each ESC\nVb_eff_0 = u_P0 * Vb;\nVb_eff_1 = u_P1 * Vb;"
-      "\nVb_eff_2 = u_P2 * Vb;\nVb_eff_3 = u_P3 * Vb;\n    \nVb_eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    27
-    ssIdNumber		    4
-    name		    "P"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [25 0 28]
-  }
-  data {
-    id			    28
-    ssIdNumber		    5
-    name		    "Vb_eff"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"1,4"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [25 27 29]
-  }
-  data {
-    id			    29
-    ssIdNumber		    16
-    name		    "Pmin"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [25 28 30]
-  }
-  data {
-    id			    30
-    ssIdNumber		    17
-    name		    "Pmax"
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [25 29 31]
-  }
-  data {
-    id			    31
-    ssIdNumber		    18
-    name		    "Vb"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 2
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [25 30 0]
-  }
-  junction {
-    id			    32
-    position		    [23.5747 49.5747 7]
-    chart		    25
-    subviewer		    25
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [25 0 0]
-  }
-  transition {
-    id			    33
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      32
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    25
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    25
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [25 0 0]
-  }
-  instance {
-    id			    34
-    machine		    1
-    name		    "Actuation/ESC System"
-    chart		    25
-  }
-  chart {
-    id			    35
-    machine		    1
-    name		    "Actuation/Motor System"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 36 0 0]
-    viewObj		    35
-    ssIdHighWaterMark	    16
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    5
-    disableImplicitCasting  1
-    eml {
-      name		      "motor"
-    }
-    firstData		    37
-    firstTransition	    47
-    firstJunction	    46
-  }
-  state {
-    id			    36
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    35
-    treeNode		    [35 0 0 0]
-    superState		    SUBCHART
-    subviewer		    35
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function w_dot = motor(Vb_eff, w, Rm, Kv, Kq, Kd, If, Jreq)\n\n% Define each motors effective bat"
-      "tery voltage\nVb_eff_0 = Vb_eff(1);\nVb_eff_1 = Vb_eff(2);\nVb_eff_2 = Vb_eff(3);\nVb_eff_3 = Vb_eff(4);\n\n% De"
-      "termine the angular velocity of each rotor from feedback\nw_0 = w(1);\nw_1 = w(2);\nw_2 = w(3);\nw_3 = w(4);\n\n"
-      "% Determine angular acceleration of each rotor\nw_0_dot = 1/(Jreq*Rm*Kq) * Vb_eff_0 - 1/(Jreq*Rm*Kq*Kv) * w_0 - "
-      "1/(Jreq*Kq)*If - (Kd/Jreq) * w_0^2;\nw_1_dot = 1/(Jreq*Rm*Kq) * Vb_eff_1 - 1/(Jreq*Rm*Kq*Kv) * w_1 - 1/(Jreq*Kq)"
-      "*If - (Kd/Jreq) * w_1^2;\nw_2_dot = 1/(Jreq*Rm*Kq) * Vb_eff_2 - 1/(Jreq*Rm*Kq*Kv) * w_2 - 1/(Jreq*Kq)*If - (Kd/J"
-      "req) * w_2^2;\nw_3_dot = 1/(Jreq*Rm*Kq) * Vb_eff_3 - 1/(Jreq*Rm*Kq*Kv) * w_3 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_3^"
-      "2;\n\nw_dot = [w_0_dot, w_1_dot, w_2_dot, w_3_dot];  "
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    37
-    ssIdNumber		    4
-    name		    "Vb_eff"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 0 38]
-  }
-  data {
-    id			    38
-    ssIdNumber		    16
-    name		    "w"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 37 39]
-  }
-  data {
-    id			    39
-    ssIdNumber		    7
-    name		    "w_dot"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"1,4"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 38 40]
-  }
-  data {
-    id			    40
-    ssIdNumber		    9
-    name		    "Rm"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 5
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 39 41]
-  }
-  data {
-    id			    41
-    ssIdNumber		    10
-    name		    "Kv"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 4
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 40 42]
-  }
-  data {
-    id			    42
-    ssIdNumber		    11
-    name		    "Kq"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 3
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 41 43]
-  }
-  data {
-    id			    43
-    ssIdNumber		    12
-    name		    "Kd"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 2
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 42 44]
-  }
-  data {
-    id			    44
-    ssIdNumber		    13
-    name		    "If"
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 43 45]
-  }
-  data {
-    id			    45
-    ssIdNumber		    14
-    name		    "Jreq"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [35 44 0]
-  }
-  junction {
-    id			    46
-    position		    [23.5747 49.5747 7]
-    chart		    35
-    subviewer		    35
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [35 0 0]
-  }
-  transition {
-    id			    47
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      46
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    35
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    35
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [35 0 0]
-  }
-  instance {
-    id			    48
-    machine		    1
-    name		    "Actuation/Motor System"
-    chart		    35
-  }
-  chart {
-    id			    49
-    machine		    1
-    name		    "Actuation/Rotor System\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 50 0 0]
-    viewObj		    49
-    ssIdHighWaterMark	    31
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    6
-    disableImplicitCasting  1
-    eml {
-      name		      "rotor"
-    }
-    firstData		    51
-    firstTransition	    69
-    firstJunction	    68
-  }
-  state {
-    id			    50
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    49
-    treeNode		    [49 0 0 0]
-    superState		    SUBCHART
-    subviewer		    49
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [B_omega_dot, B_vo_dot]= rotor(w_dot, w, B_Fg, B_omega, B_vo, m, Kt, Kd, rhx, rhy, rhz, "
-      "Jreq, Jxx, Jyy, Jzz)\n\n% Create J vector\nJ = [Jxx,  0 ,  0 ; ...\n      0 , Jyy,  0 ; ...\n      0 ,  0 , Jzz;"
-      "];\n\n% Create r_hi vector\nrh_0 = [-rhx; rhy; -rhz];\nrh_1 = [rhx; rhy; -rhz];\nrh_2 = [-rhx; -rhy; -rhz];\nrh_"
-      "3 = [rhx; -rhy; -rhz];\n\n% Define vector from body frame origin to center of mass\nbr_oc = [0; 0; 0];\n\n% Defi"
-      "ne 3x3 Identity Matrix\nI = eye(3);\n\n% Create gamma vectors\ngamma_Ti = [0; 0; -1];\ngamma_omega_03 = [0; 0; 1"
-      "];  %Rotors 0 and 3 use this gamma_omega vector\ngamma_omega_12 = [0; 0; -1]; %Rotors 1 and 2 use this gamma_ome"
-      "ga vector\n\n% Define angular velocities for each rotor\nw_0 = w(1);\nw_1 = w(2);\nw_2 = w(3);\nw_3 = w(4);\n\n%"
-      " Define angular acceleration for each rotor\nw_0_dot = w_dot(1);\nw_1_dot = w_dot(2);\nw_2_dot = w_dot(3);\nw_3_"
-      "dot = w_dot(4);\n\n% Define the rotor force in the z-direction from each rotor\nB_Fr_0 = Kt * w_0 * w_0 * gamma_"
-      "Ti;\nB_Fr_1 = Kt * w_1 * w_1 * gamma_Ti;\nB_Fr_2 = Kt * w_2 * w_2 * gamma_Ti;\nB_Fr_3 = Kt * w_3 * w_3 * gamma_T"
-      "i;\n\n% Sum up the rotor forces in the z-direction from each vector to get the\n% total body force in the z-dire"
-      "ction\nB_Fr = B_Fr_0 + B_Fr_1 + B_Fr_2 + B_Fr_3;\n\n% Define the in-plane drag and induced torque produced by ea"
-      "ch rotor\n B_Q_d0 = -1 * Kd * w_0 * w_0 * gamma_omega_03;\n B_Q_d1 = -1 * Kd * w_1 * w_1 * gamma_omega_12;\n B_Q"
-      "_d2 = -1 * Kd * w_2 * w_2 * gamma_omega_12;\n B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;\n\n% Sum up the tot"
-      "al in-plane drag and induced torque to get the total\n% in-plane drag and induced torque on the body\nB_Q_d = B_"
-      "Q_d0 + B_Q_d1 + B_Q_d2 + B_Q_d3;\n\n% Define the force lever arm torque created from the force produced by each\n"
-      "% rotor in the z-direction\nB_Q_F0 = cross( rh_0, B_Fr_0 );\nB_Q_F1 = cross( rh_1, B_Fr_1 );\nB_Q_F2 = cross( rh"
-      "_2, B_Fr_2 );\nB_Q_F3 = cross( rh_3, B_Fr_3 );\n\nB_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;\n\n%Define the chan"
-      "ge in angular momentum torque produced by each rotor \nB_Q_L0 = -1 * Jreq * ( cross(B_omega, w_0 * gamma_omega_0"
-      "3) + w_0_dot * gamma_omega_03 );\nB_Q_L1 = -1 * Jreq * ( cross(B_omega, w_1 * gamma_omega_12) + w_1_dot * gamma_"
-      "omega_12 ); \nB_Q_L2 = -1 * Jreq * ( cross(B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_omega_12 ); \nB_Q_L3"
-      " = -1 * Jreq * ( cross(B_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );\n\n% Sum up the total change"
-      " in angular momentum torque produced by each rotor\nB_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;\n\n% Define the t"
-      "otal rotor system torque as the sum of the in-plane drag and\n% induced torque, force lever arm torque, and chan"
-      "ge in angular momentum\n% torques\nB_Q = B_Q_d + B_Q_F + B_Q_L;\n\n% Define the body forces in the z-direction f"
-      "rom each vector to get the\n% total body force in the z-direction\nB_F = B_Fr + B_Fg; \n\n% Define the body fram"
-      "e linear velocities\nB_vo_dot = (m*I)^(-1) * ( B_F - cross( B_omega, m*(B_vo + cross(B_omega, br_oc)) ) );\n\n% "
-      "Define the body frame angular velocities\nB_omega_dot = J ^(-1) * ( B_Q - cross(B_omega, J * B_omega) - cross(br"
-      "_oc, B_F) );\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    51
-    ssIdNumber		    6
-    name		    "B_omega_dot"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 0 52]
-  }
-  data {
-    id			    52
-    ssIdNumber		    10
-    name		    "w_dot"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 51 53]
-  }
-  data {
-    id			    53
-    ssIdNumber		    11
-    name		    "w"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 52 54]
-  }
-  data {
-    id			    54
-    ssIdNumber		    30
-    name		    "B_Fg"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 53 55]
-  }
-  data {
-    id			    55
-    ssIdNumber		    8
-    name		    "B_omega"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 54 56]
-  }
-  data {
-    id			    56
-    ssIdNumber		    5
-    name		    "B_vo_dot"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 55 57]
-  }
-  data {
-    id			    57
-    ssIdNumber		    7
-    name		    "B_vo"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 56 58]
-  }
-  data {
-    id			    58
-    ssIdNumber		    12
-    name		    "m"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 6
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 57 59]
-  }
-  data {
-    id			    59
-    ssIdNumber		    14
-    name		    "Kt"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 5
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 58 60]
-  }
-  data {
-    id			    60
-    ssIdNumber		    13
-    name		    "Kd"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 4
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 59 61]
-  }
-  data {
-    id			    61
-    ssIdNumber		    15
-    name		    "rhx"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 7
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 60 62]
-  }
-  data {
-    id			    62
-    ssIdNumber		    16
-    name		    "rhy"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 8
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 61 63]
-  }
-  data {
-    id			    63
-    ssIdNumber		    17
-    name		    "rhz"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 9
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 62 64]
-  }
-  data {
-    id			    64
-    ssIdNumber		    18
-    name		    "Jreq"
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 63 65]
-  }
-  data {
-    id			    65
-    ssIdNumber		    19
-    name		    "Jxx"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 64 66]
-  }
-  data {
-    id			    66
-    ssIdNumber		    20
-    name		    "Jyy"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 2
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 65 67]
-  }
-  data {
-    id			    67
-    ssIdNumber		    21
-    name		    "Jzz"
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 3
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [49 66 0]
-  }
-  junction {
-    id			    68
-    position		    [23.5747 49.5747 7]
-    chart		    49
-    subviewer		    49
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [49 0 0]
-  }
-  transition {
-    id			    69
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      68
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    49
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    49
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [49 0 0]
-  }
-  instance {
-    id			    70
-    machine		    1
-    name		    "Actuation/Rotor System\n\n\n\n\n\n\n\n"
-    chart		    49
-  }
-  chart {
-    id			    71
-    machine		    1
-    name		    "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 72 0 0]
-    viewObj		    71
-    ssIdHighWaterMark	    6
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    7
-    disableImplicitCasting  1
-    eml {
-      name		      "angular_body_earth_conversion"
-    }
-    firstData		    73
-    firstTransition	    77
-    firstJunction	    76
-  }
-  state {
-    id			    72
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    71
-    treeNode		    [71 0 0 0]
-    superState		    SUBCHART
-    subviewer		    71
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function euler_rates = angular_body_earth_conversion(B_omega, euler_angles)\n\nphi = euler_angles"
-      "(1);\ntheta = euler_angles(2);\n\nAeb = [1,  sin(phi)*tan(theta), cos(phi)*tan(theta); ...\n       0,      cos(p"
-      "hi)       ,        -sin(phi)   ; ...\n       0,  sin(phi)/cos(theta), cos(phi)/cos(theta)];\n\n   \neuler_rates "
-      "= Aeb * B_omega;\n  "
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    73
-    ssIdNumber		    4
-    name		    "B_omega"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [71 0 74]
-  }
-  data {
-    id			    74
-    ssIdNumber		    5
-    name		    "euler_rates"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [71 73 75]
-  }
-  data {
-    id			    75
-    ssIdNumber		    6
-    name		    "euler_angles"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [71 74 0]
-  }
-  junction {
-    id			    76
-    position		    [23.5747 49.5747 7]
-    chart		    71
-    subviewer		    71
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [71 0 0]
-  }
-  transition {
-    id			    77
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      76
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    71
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    71
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [71 0 0]
-  }
-  instance {
-    id			    78
-    machine		    1
-    name		    "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    chart		    71
-  }
-  chart {
-    id			    79
-    machine		    1
-    name		    "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 80 0 0]
-    viewObj		    79
-    ssIdHighWaterMark	    13
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    8
-    disableImplicitCasting  1
-    eml {
-      name		      "linear_earth_body_conversion"
-    }
-    firstData		    81
-    firstTransition	    87
-    firstJunction	    86
-  }
-  state {
-    id			    80
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    79
-    treeNode		    [79 0 0 0]
-    superState		    SUBCHART
-    subviewer		    79
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [B_Fg, B_g]  = linear_earth_body_conversion(E_Fg, euler_angles, m)\n\nphi = euler_angles"
-      "(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLbe = [             cos(theta)*cos(psi)              ,"
-      "          cos(theta)*sin(psi)                  ,     -sin(theta)    ; ...\n       sin(phi)*sin(theta)*cos(psi)-c"
-      "os(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...\n       cos(phi)*sin("
-      "theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];\n\nB_Fg"
-      " = Lbe * E_Fg;\n\nB_g = B_Fg/m;"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    81
-    ssIdNumber		    7
-    name		    "E_Fg"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [79 0 82]
-  }
-  data {
-    id			    82
-    ssIdNumber		    11
-    name		    "euler_angles"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"3"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [79 81 83]
-  }
-  data {
-    id			    83
-    ssIdNumber		    9
-    name		    "B_Fg"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"3"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [79 82 84]
-  }
-  data {
-    id			    84
-    ssIdNumber		    12
-    name		    "B_g"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [79 83 85]
-  }
-  data {
-    id			    85
-    ssIdNumber		    13
-    name		    "m"
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [79 84 0]
-  }
-  junction {
-    id			    86
-    position		    [23.5747 49.5747 7]
-    chart		    79
-    subviewer		    79
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [79 0 0]
-  }
-  transition {
-    id			    87
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      86
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    79
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    79
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [79 0 0]
-  }
-  instance {
-    id			    88
-    machine		    1
-    name		    "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    chart		    79
-  }
-  chart {
-    id			    89
-    machine		    1
-    name		    "     Sensors   /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 90 0 0]
-    viewObj		    89
-    ssIdHighWaterMark	    15
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    10
-    disableImplicitCasting  1
-    eml {
-      name		      "idealIMU"
-    }
-    firstData		    91
-    firstTransition	    100
-    firstJunction	    99
-  }
-  state {
-    id			    90
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    89
-    treeNode		    [89 0 0 0]
-    superState		    SUBCHART
-    subviewer		    89
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [accelReading,gyroReading] = idealIMU(B_vo_dot, B_vo, B_Omega, B_g, r_oc, g)\n%#codegen\n"
-      "\na = B_vo_dot + cross(B_Omega,B_vo); % body frame acceleration \n\naccelReading = (a - B_g)/g ; % accelerometer"
-      " reading (ideal)\n\ngyroReading = B_Omega ; % gyroscope reading (ideal) \n\nend\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    91
-    ssIdNumber		    4
-    name		    "B_vo_dot"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 0 92]
-  }
-  data {
-    id			    92
-    ssIdNumber		    9
-    name		    "B_vo"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 91 93]
-  }
-  data {
-    id			    93
-    ssIdNumber		    5
-    name		    "accelReading"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 92 94]
-  }
-  data {
-    id			    94
-    ssIdNumber		    6
-    name		    "B_Omega"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 93 95]
-  }
-  data {
-    id			    95
-    ssIdNumber		    7
-    name		    "B_g"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 94 96]
-  }
-  data {
-    id			    96
-    ssIdNumber		    8
-    name		    "gyroReading"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 95 97]
-  }
-  data {
-    id			    97
-    ssIdNumber		    10
-    name		    "r_oc"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 96 98]
-  }
-  data {
-    id			    98
-    ssIdNumber		    12
-    name		    "g"
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [89 97 0]
-  }
-  junction {
-    id			    99
-    position		    [23.5747 49.5747 7]
-    chart		    89
-    subviewer		    89
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [89 0 0]
-  }
-  transition {
-    id			    100
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      99
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    89
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    89
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [89 0 0]
-  }
-  instance {
-    id			    101
-    machine		    1
-    name		    "     Sensors   /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n"
-    chart		    89
-  }
-  chart {
-    id			    102
-    machine		    1
-    name		    "     Sensors   /3D Graphical Simulation/MATLAB Function"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 103 0 0]
-    viewObj		    102
-    ssIdHighWaterMark	    5
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    11
-    disableImplicitCasting  1
-    eml {
-      name		      "eigenaxis_ucart"
-    }
-    firstData		    104
-    firstTransition	    107
-    firstJunction	    106
-  }
-  state {
-    id			    103
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    102
-    treeNode		    [102 0 0 0]
-    superState		    SUBCHART
-    subviewer		    102
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n    u(1) = 0.0001;\nend\n\nif abs(u(2)"
-      ")< 0.0001\n    u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n    u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) "
-      "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin("
-      "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = "
-      "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u("
-      "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n    \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; "
-      "C31-C13; C12-C21]/(2*sin(theta));\n    \ny = [e; theta];\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    104
-    ssIdNumber		    4
-    name		    "u"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [102 0 105]
-  }
-  data {
-    id			    105
-    ssIdNumber		    5
-    name		    "y"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [102 104 0]
-  }
-  junction {
-    id			    106
-    position		    [23.5747 49.5747 7]
-    chart		    102
-    subviewer		    102
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [102 0 0]
-  }
-  transition {
-    id			    107
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      106
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    102
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    102
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [102 0 0]
-  }
-  instance {
-    id			    108
-    machine		    1
-    name		    "     Sensors   /3D Graphical Simulation/MATLAB Function"
-    chart		    102
-  }
-  chart {
-    id			    109
-    machine		    1
-    name		    "     Sensors   /Aeb\n\n\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 110 0 0]
-    viewObj		    109
-    ssIdHighWaterMark	    6
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    12
-    disableImplicitCasting  1
-    eml {
-      name		      "angular_body_earth_conversion"
-    }
-    firstData		    111
-    firstTransition	    115
-    firstJunction	    114
-  }
-  state {
-    id			    110
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    109
-    treeNode		    [109 0 0 0]
-    superState		    SUBCHART
-    subviewer		    109
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_filtered)\n\n"
-      "phi = euler_angles_filtered(1);\ntheta = euler_angles_filtered(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*ta"
-      "n(theta); ...\n       0,     cos(phi)       ,        -sin(phi)   ; ...\n       0,  sin(phi)/cos(theta), cos(phi)"
-      "/cos(theta)];\n\n   \neuler_rates_IMU = Aeb * gyro_reading;\n  "
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    111
-    ssIdNumber		    4
-    name		    "gyro_reading"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [109 0 112]
-  }
-  data {
-    id			    112
-    ssIdNumber		    5
-    name		    "euler_rates_IMU"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"[3,1]"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [109 111 113]
-  }
-  data {
-    id			    113
-    ssIdNumber		    6
-    name		    "euler_angles_filtered"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [109 112 0]
-  }
-  junction {
-    id			    114
-    position		    [23.5747 49.5747 7]
-    chart		    109
-    subviewer		    109
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [109 0 0]
-  }
-  transition {
-    id			    115
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      114
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    109
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    109
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [109 0 0]
-  }
-  instance {
-    id			    116
-    machine		    1
-    name		    "     Sensors   /Aeb\n\n\n\n\n\n\n\n\n\n"
-    chart		    109
-  }
-  chart {
-    id			    117
-    machine		    1
-    name		    "     Sensors   /Calculate Pitch and Roll"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 118 0 0]
-    viewObj		    117
-    ssIdHighWaterMark	    10
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    13
-    disableImplicitCasting  1
-    eml {
-      name		      "getPitchAndRoll"
-    }
-    firstData		    119
-    firstTransition	    124
-    firstJunction	    123
-  }
-  state {
-    id			    118
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    117
-    treeNode		    [117 0 0 0]
-    superState		    SUBCHART
-    subviewer		    117
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [accel_pitch, accel_roll] = getPitchAndRoll(accel_reading, accel_roll_prev)\n\nmag = nor"
-      "m(accel_reading);\n\n% x_accel = accel_reading(1)/mag;\n% y_accel = accel_reading(2)/mag;\n% z_accel = accel_rea"
-      "ding(3)/mag;\n\nx_accel = accel_reading(1);\ny_accel = accel_reading(2);\nz_accel = accel_reading(3);\n\naccel_p"
-      "itch = atan(x_accel/sqrt(y_accel^2 + z_accel^2));\n\n%accel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^"
-      "2 + (1/100)*x_accel^2)) );\n\n%accel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^2 + x_accel^2)) );\nacc"
-      "el_roll = atan( -y_accel/( sqrt(z_accel^2 + x_accel^2))  );\n\n% unwrapped_roll = unwrap([accel_roll_prev accel_"
-      "roll]);\n% accel_roll = unwrapped_roll(2);\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    119
-    ssIdNumber		    4
-    name		    "accel_reading"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [117 0 120]
-  }
-  data {
-    id			    120
-    ssIdNumber		    5
-    name		    "accel_pitch"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [117 119 121]
-  }
-  data {
-    id			    121
-    ssIdNumber		    6
-    name		    "accel_roll"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [117 120 122]
-  }
-  data {
-    id			    122
-    ssIdNumber		    7
-    name		    "accel_roll_prev"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [117 121 0]
-  }
-  junction {
-    id			    123
-    position		    [23.5747 49.5747 7]
-    chart		    117
-    subviewer		    117
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [117 0 0]
-  }
-  transition {
-    id			    124
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      123
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    117
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    117
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [117 0 0]
-  }
-  instance {
-    id			    125
-    machine		    1
-    name		    "     Sensors   /Calculate Pitch and Roll"
-    chart		    117
-  }
-  chart {
-    id			    126
-    machine		    1
-    name		    "Control System/Signal Mixer"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 127 0 0]
-    viewObj		    126
-    ssIdHighWaterMark	    11
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    14
-    disableImplicitCasting  1
-    eml {
-      name		      "signal_mixer"
-    }
-    firstData		    128
-    firstTransition	    134
-    firstJunction	    133
-  }
-  state {
-    id			    127
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    126
-    treeNode		    [126 0 0 0]
-    superState		    SUBCHART
-    subviewer		    126
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function P  = signal_mixer(height_controlled, y_controlled, x_controlled, yaw_controlled)\n\ncont"
-      "roller_outputs = [ height_controlled; x_controlled; y_controlled; yaw_controlled ];\nsignal_mixer = [ 1, -1, -1,"
-      " -1; ... \n                 1,  1, -1,  1; ...\n                 1, -1,  1,  1; ...\n                 1,  1,  1,"
-      " -1 ];\n\n% signal_mixer = [ 1,  1, -1, -1; ... \n%                  1, -1, -1,  1; ...\n%                  1,  "
-      "1,  1,  1; ...\n%                  1, -1,  1, -1 ];\n             \nP = signal_mixer * controller_outputs;\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    128
-    ssIdNumber		    4
-    name		    "height_controlled"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [126 0 129]
-  }
-  data {
-    id			    129
-    ssIdNumber		    7
-    name		    "y_controlled"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [126 128 130]
-  }
-  data {
-    id			    130
-    ssIdNumber		    5
-    name		    "P"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [126 129 131]
-  }
-  data {
-    id			    131
-    ssIdNumber		    6
-    name		    "x_controlled"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [126 130 132]
-  }
-  data {
-    id			    132
-    ssIdNumber		    8
-    name		    "yaw_controlled"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [126 131 0]
-  }
-  junction {
-    id			    133
-    position		    [23.5747 49.5747 7]
-    chart		    126
-    subviewer		    126
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [126 0 0]
-  }
-  transition {
-    id			    134
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      133
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    126
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    126
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [126 0 0]
-  }
-  instance {
-    id			    135
-    machine		    1
-    name		    "Control System/Signal Mixer"
-    chart		    126
-  }
-  chart {
-    id			    136
-    machine		    1
-    name		    "Control System/MATLAB Function1"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 137 0 0]
-    viewObj		    136
-    ssIdHighWaterMark	    25
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    15
-    disableImplicitCasting  1
-    eml {
-      name		      "c_controller"
-    }
-    firstData		    138
-    firstTransition	    160
-    firstJunction	    159
-  }
-  state {
-    id			    137
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    136
-    treeNode		    [136 0 0 0]
-    superState		    SUBCHART
-    subviewer		    136
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [z_corr, y_cor, x_corr, yaw_corr, pid_y_out, pid_roll_out] = c_controller(set_x, set_y, "
-      "set_z, set_yaw, ...\n    cur_x, cur_y, cur_z, ...\n    cur_phi, cur_theta, cur_psi, ...\n    cur_phi_d, cur_thet"
-      "a_d, cur_psi_d, vrpn_id, Tc)\n\nout_z = -1;\nout_y = -1;\nout_x = -1;\nout_yaw = -1;\nc_pid_y = -1;\nc_pid_roll "
-      "= -1;\n\ncoder.ceval('c_controller', vrpn_id, Tc, set_x, set_y, set_z, set_yaw, ...\n                    cur_x, "
-      "cur_y, cur_z, ...\n                    cur_phi, cur_theta, cur_psi, ...\n                    cur_phi_d, cur_thet"
-      "a_d, cur_psi_d, ...\n                    coder.wref(out_z), coder.wref(out_y), coder.wref(out_x), coder.wref(out"
-      "_yaw), ...\n                    coder.wref(c_pid_y), coder.wref(c_pid_roll));\n\nz_corr = out_z;\ny_cor = out_y;"
-      "\nx_corr = out_x;\npid_y_out = c_pid_y;\npid_roll_out = c_pid_roll;\nyaw_corr = out_yaw;\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    138
-    ssIdNumber		    4
-    name		    "set_x"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 0 139]
-  }
-  data {
-    id			    139
-    ssIdNumber		    5
-    name		    "z_corr"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 138 140]
-  }
-  data {
-    id			    140
-    ssIdNumber		    6
-    name		    "set_y"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 139 141]
-  }
-  data {
-    id			    141
-    ssIdNumber		    7
-    name		    "set_z"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 140 142]
-  }
-  data {
-    id			    142
-    ssIdNumber		    8
-    name		    "set_yaw"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 141 143]
-  }
-  data {
-    id			    143
-    ssIdNumber		    9
-    name		    "cur_x"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 142 144]
-  }
-  data {
-    id			    144
-    ssIdNumber		    10
-    name		    "cur_y"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 143 145]
-  }
-  data {
-    id			    145
-    ssIdNumber		    11
-    name		    "cur_z"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 144 146]
-  }
-  data {
-    id			    146
-    ssIdNumber		    12
-    name		    "cur_phi"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 145 147]
-  }
-  data {
-    id			    147
-    ssIdNumber		    13
-    name		    "cur_theta"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 146 148]
-  }
-  data {
-    id			    148
-    ssIdNumber		    14
-    name		    "cur_psi"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 147 149]
-  }
-  data {
-    id			    149
-    ssIdNumber		    15
-    name		    "cur_phi_d"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 148 150]
-  }
-  data {
-    id			    150
-    ssIdNumber		    16
-    name		    "cur_theta_d"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 149 151]
-  }
-  data {
-    id			    151
-    ssIdNumber		    17
-    name		    "cur_psi_d"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 150 152]
-  }
-  data {
-    id			    152
-    ssIdNumber		    18
-    name		    "y_cor"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 151 153]
-  }
-  data {
-    id			    153
-    ssIdNumber		    19
-    name		    "x_corr"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 152 154]
-  }
-  data {
-    id			    154
-    ssIdNumber		    20
-    name		    "yaw_corr"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 153 155]
-  }
-  data {
-    id			    155
-    ssIdNumber		    21
-    name		    "vrpn_id"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 154 156]
-  }
-  data {
-    id			    156
-    ssIdNumber		    22
-    name		    "pid_y_out"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 155 157]
-  }
-  data {
-    id			    157
-    ssIdNumber		    23
-    name		    "pid_roll_out"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 156 158]
-  }
-  data {
-    id			    158
-    ssIdNumber		    25
-    name		    "Tc"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [136 157 0]
-  }
-  junction {
-    id			    159
-    position		    [23.5747 49.5747 7]
-    chart		    136
-    subviewer		    136
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [136 0 0]
-  }
-  transition {
-    id			    160
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      159
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    136
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    136
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [136 0 0]
-  }
-  instance {
-    id			    161
-    machine		    1
-    name		    "Control System/MATLAB Function1"
-    chart		    136
-  }
-  chart {
-    id			    162
-    machine		    1
-    name		    "     Sensors   /Aeb_c\n\n\n\n\n\n\n\n\n\n1"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 163 0 0]
-    viewObj		    162
-    ssIdHighWaterMark	    6
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    16
-    disableImplicitCasting  1
-    eml {
-      name		      "angular_body_earth_conversion"
-    }
-    firstData		    164
-    firstTransition	    168
-    firstJunction	    167
-  }
-  state {
-    id			    163
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    162
-    treeNode		    [162 0 0 0]
-    superState		    SUBCHART
-    subviewer		    162
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_filtered)\n\n"
-      "phi = euler_angles_filtered(1);\ntheta = euler_angles_filtered(2);\npsi = NaN;\n\nphi_dot = -1;\ntheta_dot = -1;"
-      "\npsi_dot = -1;\n\np = gyro_reading(1);\nq = gyro_reading(2);\nr = gyro_reading(3);\n\ncoder.ceval( 'aeb_mat', p"
-      ", q, r, phi, theta, psi, coder.wref(phi_dot), ...\n    coder.wref(theta_dot), coder.wref(psi_dot) );\n\n   \neul"
-      "er_rates_IMU = [phi_dot; theta_dot; psi_dot];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    164
-    ssIdNumber		    4
-    name		    "gyro_reading"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [162 0 165]
-  }
-  data {
-    id			    165
-    ssIdNumber		    5
-    name		    "euler_rates_IMU"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"[3,1]"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [162 164 166]
-  }
-  data {
-    id			    166
-    ssIdNumber		    6
-    name		    "euler_angles_filtered"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [162 165 0]
-  }
-  junction {
-    id			    167
-    position		    [23.5747 49.5747 7]
-    chart		    162
-    subviewer		    162
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [162 0 0]
-  }
-  transition {
-    id			    168
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      167
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    162
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    162
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [162 0 0]
-  }
-  instance {
-    id			    169
-    machine		    1
-    name		    "     Sensors   /Aeb_c\n\n\n\n\n\n\n\n\n\n1"
-    chart		    162
-  }
-  chart {
-    id			    170
-    machine		    1
-    name		    "     Sensors   /MATLAB Function"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 171 0 0]
-    viewObj		    170
-    ssIdHighWaterMark	    7
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    17
-    disableImplicitCasting  1
-    eml {
-      name		      "complimentaryFilterC"
-    }
-    firstData		    172
-    firstTransition	    177
-    firstJunction	    176
-  }
-  state {
-    id			    171
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    170
-    treeNode		    [170 0 0 0]
-    superState		    SUBCHART
-    subviewer		    170
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function euler_angles_IMU  = complimentaryFilterC(accel_pitch, accel_roll, euler_rates_gyro)\n\ne"
-      "uler_x = euler_rates_gyro(1);\neuler_y = euler_rates_gyro(2);\n\nfiltered_pitch = -1;\nfiltered_roll = -1;\n\nco"
-      "der.ceval('compl_filter', accel_pitch, accel_roll, euler_x, euler_y, ...\n            coder.wref(filtered_pitch)"
-      ", coder.wref(filtered_roll));\n\neuler_angles_IMU = [filtered_roll; filtered_pitch];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    172
-    ssIdNumber		    4
-    name		    "accel_pitch"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [170 0 173]
-  }
-  data {
-    id			    173
-    ssIdNumber		    5
-    name		    "euler_angles_IMU"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [170 172 174]
-  }
-  data {
-    id			    174
-    ssIdNumber		    6
-    name		    "accel_roll"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [170 173 175]
-  }
-  data {
-    id			    175
-    ssIdNumber		    7
-    name		    "euler_rates_gyro"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [170 174 0]
-  }
-  junction {
-    id			    176
-    position		    [23.5747 49.5747 7]
-    chart		    170
-    subviewer		    170
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [170 0 0]
-  }
-  transition {
-    id			    177
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      176
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    170
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    170
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [170 0 0]
-  }
-  instance {
-    id			    178
-    machine		    1
-    name		    "     Sensors   /MATLAB Function"
-    chart		    170
-  }
-  chart {
-    id			    179
-    machine		    1
-    name		    "     Sensors   /MATLAB Function1"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 180 0 0]
-    viewObj		    179
-    ssIdHighWaterMark	    6
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    18
-    disableImplicitCasting  1
-    eml {
-      name		      "angle_IMU_C"
-    }
-    firstData		    181
-    firstTransition	    185
-    firstJunction	    184
-  }
-  state {
-    id			    180
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    179
-    treeNode		    [179 0 0 0]
-    superState		    SUBCHART
-    subviewer		    179
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [accel_pitch, accel_roll]  = angle_IMU_C(accel_reading)\n\naccel_x = accel_reading(1);\n"
-      "accel_y = accel_reading(2);\naccel_z = accel_reading(3);\n\ncalculated_pitch = -1;\ncalculated_roll = -1;\n\ncod"
-      "er.ceval('angle_accel', accel_x, accel_y, accel_z, coder.wref(calculated_pitch), coder.wref(calculated_roll));\n"
-      "\naccel_pitch = calculated_pitch;\naccel_roll = calculated_roll;"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    181
-    ssIdNumber		    4
-    name		    "accel_reading"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [179 0 182]
-  }
-  data {
-    id			    182
-    ssIdNumber		    5
-    name		    "accel_pitch"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [179 181 183]
-  }
-  data {
-    id			    183
-    ssIdNumber		    6
-    name		    "accel_roll"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [179 182 0]
-  }
-  junction {
-    id			    184
-    position		    [23.5747 49.5747 7]
-    chart		    179
-    subviewer		    179
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [179 0 0]
-  }
-  transition {
-    id			    185
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      184
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    179
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    179
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [179 0 0]
-  }
-  instance {
-    id			    186
-    machine		    1
-    name		    "     Sensors   /MATLAB Function1"
-    chart		    179
-  }
-  chart {
-    id			    187
-    machine		    1
-    name		    "     Sensors   /Complimentary Filter"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 188 0 0]
-    viewObj		    187
-    ssIdHighWaterMark	    17
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    chartFileNumber	    19
-    disableImplicitCasting  1
-    eml {
-      name		      "complimentaryFilter"
-    }
-    firstData		    189
-    firstTransition	    195
-    firstJunction	    194
-  }
-  state {
-    id			    188
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    187
-    treeNode		    [187 0 0 0]
-    superState		    SUBCHART
-    subviewer		    187
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "%function euler_angles_IMU  = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro, pre"
-      "v_euler_angles_IMU)\nfunction euler_angles_IMU  = complimentaryFilter(accel_pitch, accel_roll, euler_rates_gyro,"
-      " prev_euler_angles)\n\nk_gyro = 0.98; \nk_accel = 1-k_gyro; \n\nTs = 0.005; % 5 milliseconds\n\nprev_phi = prev_"
-      "euler_angles(1);\nprev_theta = prev_euler_angles(2);\n\nprev_phi_dot = euler_rates_gyro(1);\nprev_theta_dot = eu"
-      "ler_rates_gyro(2);\n\nintegrated_phi_gyro = Ts * prev_phi_dot + prev_phi;\nintegrated_theta_gyro = Ts * prev_the"
-      "ta_dot + prev_theta;\n\nphi = k_gyro * integrated_phi_gyro + k_accel * accel_roll;\ntheta = k_gyro * integrated_"
-      "theta_gyro + k_accel * accel_pitch;\n\neuler_angles_IMU = [phi; theta];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    189
-    ssIdNumber		    4
-    name		    "accel_pitch"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [187 0 190]
-  }
-  data {
-    id			    190
-    ssIdNumber		    13
-    name		    "accel_roll"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [187 189 191]
-  }
-  data {
-    id			    191
-    ssIdNumber		    5
-    name		    "euler_angles_IMU"
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"[2,1]"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [187 190 192]
-  }
-  data {
-    id			    192
-    ssIdNumber		    6
-    name		    "euler_rates_gyro"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [187 191 193]
-  }
-  data {
-    id			    193
-    ssIdNumber		    17
-    name		    "prev_euler_angles"
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-    linkNode		    [187 192 0]
-  }
-  junction {
-    id			    194
-    position		    [23.5747 49.5747 7]
-    chart		    187
-    subviewer		    187
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-    linkNode		    [187 0 0]
-  }
-  transition {
-    id			    195
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      194
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    187
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    187
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-    linkNode		    [187 0 0]
-  }
-  instance {
-    id			    196
-    machine		    1
-    name		    "     Sensors   /Complimentary Filter"
-    chart		    187
-  }
-  target {
-    id			    197
-    machine		    1
-    name		    "sfun"
-    description		    "Default Simulink S-Function Target."
-    linkNode		    [1 0 0]
-  }
-}
diff --git a/controls/model/Quadcopter_Model_R2016_A.slx b/controls/model/Quadcopter_Model_R2016_A.slx
deleted file mode 100644
index 7f461495c2c37f501f258aed80ec8233b134740b..0000000000000000000000000000000000000000
Binary files a/controls/model/Quadcopter_Model_R2016_A.slx and /dev/null differ
diff --git a/controls/model/Quadcopter_Model_R2016_B.slx b/controls/model/Quadcopter_Model_R2016_B.slx
deleted file mode 100644
index 9ddda3cdbd05db65d455a676fe14b5b871b4b78c..0000000000000000000000000000000000000000
Binary files a/controls/model/Quadcopter_Model_R2016_B.slx and /dev/null differ
diff --git a/controls/model/improved_lqr.m b/controls/model/improved_lqr.m
new file mode 100644
index 0000000000000000000000000000000000000000..316a93eaff63038d0ce470920cf658512c5d0da5
--- /dev/null
+++ b/controls/model/improved_lqr.m
@@ -0,0 +1,22 @@
+% Given the state-space linearization, diagonal weighting matrices, and
+% update period, compute the discrete LQR model for the system, described
+% in Matt Rich's thesis section 7.4. Unlike the "initial LQR" design, this
+% version defines its cost function with block-diagonal weighting matrices
+% (instead of purely diagonal matrices)
+
+% c_alt, c_lat, and c_dir are 3x2, 1x4, and 3x2, respectively
+function [lqr_K, lqr_S, lqr_E] = improved_lqr(A, B, c_alt, c_lat, c_dir, d_alt, d_lat, d_dir, T)
+    % Given the block-diagonal weighting matrix, index ordering permutation
+    % to get the controller in our previous state ordering
+    perm = [7 3 1 5 9 11 8 4 2 6 10 12];
+    % Longitudinal is the same as latidude, but the angular weights need to
+    % be flipped
+    d_long = -d_lat;
+    c_long = [c_lat(1:2), -c_lat(3:4)];
+    % Q, R, and N matrices from weighting, given in subsytem components
+    Q_sub = blkdiag(c_alt'*c_alt, c_lat'*c_lat, c_long'*c_long, c_dir'*c_dir);
+    R_sub = blkdiag(d_alt'*d_alt, d_lat'*d_lat, d_long'*d_long, d_dir'*d_dir);
+    N_sub = blkdiag(c_alt'*d_alt, c_lat'*d_lat, c_long'*d_long, c_dir'*d_dir);
+    % Permute subsystem-ordered matrices to get compatible controller
+    [lqr_K, lqr_S, lqr_E] = lqrd(A, B, Q_sub(perm,perm), R_sub, N_sub(perm,:), T);
+end
\ No newline at end of file
diff --git a/controls/model/initial_lqr.m b/controls/model/initial_lqr.m
new file mode 100644
index 0000000000000000000000000000000000000000..9db5ec1150588c4d4d06b0888850dde6a1bdc96b
--- /dev/null
+++ b/controls/model/initial_lqr.m
@@ -0,0 +1,8 @@
+% Given the state-space linearization, diagonal weighting matrices, and
+% update period, compute the discrete LQR model for the system, described
+% in Matt Rich's thesis section 7.3
+function [lqr_K, lqr_S, lqr_E] = initial_lqr(A, B, state_weights, command_weights, T)
+    lqr_Q = diag(1./state_weights.^2);
+    lqr_R = diag(1./command_weights.^2);
+    [lqr_K, lqr_S, lqr_E] = lqrd(A, B, lqr_Q, lqr_R, zeros(12, 4), T);
+end
\ No newline at end of file
diff --git a/controls/model/linearization.m b/controls/model/linearization.m
new file mode 100644
index 0000000000000000000000000000000000000000..75de8cf7b1a71d8cce6a33f894d8c200d0964c9b
--- /dev/null
+++ b/controls/model/linearization.m
@@ -0,0 +1,130 @@
+% Implements the nonlinear model and creates state-space matrices A and B
+% using MATLAB's symbolic differentiation.
+%
+% The model physics is taken from Matt Rich's "Model Development..."
+% sections 4.1 and 4.2
+%
+% This linearization assumes the rotor orientation in the simulink model:
+% 1     2
+%   +dx
+%      +dy
+%
+% 3     4
+% In some of the internal simulink files, these are indexed 0, ..., 3
+% instead of 1, .., 4. The order is unchanged. 
+% Note that the final result should be the same regardless of rotor
+% orientation, but everything internal to this function and its parameters
+% need to be consistent.
+function [A, B] = linearization(m, g, Kt, Kh, Kd, delta_T_z, rx, ry, rz, J, Jreq, Vb, Rm, Kv, Kq, If, signal_mixer)
+    % Symbolic state variables
+    syms u v w p q r x y z ph th ps
+    
+    % Rotation matrices. After linearization, these are equivalent to I
+    L_EB = [...
+        cos(th)*cos(ps), sin(ph)*sin(th)*cos(ps)-cos(ph)*sin(ps), cos(ph)*sin(th)*cos(ps)+sin(ph)*sin(ps)
+        cos(th)*sin(ps), sin(ph)*sin(th)*sin(ps)+cos(ph)*cos(ps), cos(ph)*sin(th)*sin(ps)-sin(ph)*cos(ps)
+        -sin(th),        sin(ph)*cos(th),                         cos(ph)*cos(th)];
+    A_EB = [...
+        1,  0,       -sin(th)
+        0,  cos(ph),  sin(ph)*cos(th)
+        0, -sin(ph),  cos(ph)*cos(th)];
+    
+    % Rotor positions
+    r_h = [...
+        -rx,  rx, -rx,  rx
+         ry,  ry, -ry, -ry
+        -rz, -rz, -rz, -rz
+    ];
+
+    % Gamma matrices select force dimensions
+    Gamma_H = diag([1, 1, 0]);
+    Gamma_Omega = [zeros(2,4); 1, -1, -1, 1];
+    
+    % uT, uA, uE, uR
+    u_c = sym('u_c_%d', [1 4]);
+    % Individual rotor commands
+    u_p = (signal_mixer * u_c')';
+    
+    % Rotor angular velocities
+    % These values assume no motor transient
+    % (i.e. speeds reached immediately)
+    omega = sym('w_%d', [1 4]);
+    for i = 1:4
+        omega(i) = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*u_p(i)*Vb)))/(2*Rm*Kv*Kq*Kd);
+    end
+    
+    % Variable vectors
+    v_B_0   = [u; v; w];
+    Omega_B = [p; q; r];
+    
+    % Rotor velocity
+    for i = 1:4
+        v_h(:,i) = v_B_0 + cross(Omega_B, r_h(:,i));
+    end
+    
+    % Gravity
+    G_B = m*g*[-sin(th); cos(th)*sin(ph); cos(th)*cos(ph)];
+    
+    % Force
+    % Rotor Thrust (3 directions x 4 rotors matrix)
+    T_B = [zeros(2, 4); -(Kt*omega.^2 + delta_T_z*v_h(3,:).*omega)];
+    % Rotor In-plane drag (3 directions x 4 rotors matrix)
+    H_B = -(Kh*ones(3,1)*omega).*(Gamma_H*v_h);
+    % Total Force (Gravity + rotor force summed over all rotors)
+    F_B = G_B + sum(T_B + H_B, 2);
+
+    % Torque
+    for i = 1:4
+        % Force Lever-arm Torque
+        Q_B_F(:,i) = cross(r_h(:,i), T_B(:,i) + H_B(:,i));
+        % Change of Angular Momentum Torque (assuming no motor transient)
+        Q_B_L(:,i) = -Jreq*cross(Omega_B, omega(i)*Gamma_Omega(:,i));
+        % Drag/Induced Torque
+        Q_B_d(:,i) = -Kd*omega(i)^2*Gamma_Omega(:,i);
+    end
+    % Total Torque
+    Q_B = sum(Q_B_F + Q_B_d + Q_B_L, 2);
+    
+    % Define state vector Lambda and its time derivative, Lambda_dot
+    Lambda = [u, v, w, p, q, r, x, y, z, ph, th, ps];
+    Lambda_dot = [...
+        1/m * F_B - cross(Omega_B, v_B_0)
+        J^-1 * Q_B - cross(J^-1 * Omega_B, J * Omega_B)
+        L_EB * v_B_0
+        A_EB * Omega_B
+    ];
+
+    % A is partial of Lambda_dot wrt Lambda
+    for i = 1:12
+        for j = 1:12
+            symA(i, j) = diff(Lambda_dot(i), Lambda(j));
+        end
+    end
+    
+    % B is partial of Lambda_dot wrt u_T, u_A, u_E, u_R
+    for i = 1:12
+        for j = 1:4
+            symB(i, j) = diff(Lambda_dot(i), u_c(j)); 
+        end
+    end
+    
+    % Set equilibrium values
+    u = 0; v = 0; w = 0; p = 0; q = 0; r = 0; x = 0; y = 0; z = 0; ph = 0; th = 0; ps = 0;
+    u_c_1 = 0; u_c_2 = 0; u_c_3 = 0; u_c_4 = 0;
+    
+    % Binary search for equilibrium throttle value
+    throttle_max = 1; throttle_min = 0;
+    while (abs(double(subs(F_B(3)))) > 1e-7)
+        u_c_1 = (throttle_max + throttle_min)/2;
+        if (double(subs(F_B(3))) > 0)
+            throttle_min = double(u_c_1);
+        else
+            throttle_max = double(u_c_1);
+        end
+    end
+    
+    % Convert symbolic linearization matrices to double values
+    A = double(subs(symA));
+    B = double(subs(symB));
+end
+%#ok<*AGROW>
\ No newline at end of file
diff --git a/controls/model/lqr_err.m b/controls/model/lqr_err.m
new file mode 100644
index 0000000000000000000000000000000000000000..fff65cd53944e86089d300a2d8c9f228f4f2b6bc
--- /dev/null
+++ b/controls/model/lqr_err.m
@@ -0,0 +1,19 @@
+% Given a set of weights and the state-space matrices, lqr_err() constructs
+% the LQR controller, runs the Simulink simulation, and computes the sum of
+% the norms of the errors of each setpoint position dimension (x, y, z,
+% roll, pitch, and yaw)
+
+% Note weights is [uv, w, pq, r, xy, z, phth, ps, uT, uAuE, uR]
+% All analogous state variables for x and y are shared to reduce dimension
+function err = lqr_err(A, B, weights, T)
+    w = weights;
+    % This re-expands the weights to length 12 and 4 vectors, respectively
+    state_weights = [w(1) w(1:3) w(3:5) w(5:7) w(7:8)];
+    command_weights = [w(9:10) w(10:11)];
+    [K, ~, ~] = initial_lqr(A, B, state_weights, command_weights, T);
+    % Set the LQR K matrix in the simulator to the newly calculated one
+    assignin('base', 'lqr_K', K);
+    % Run Simulink simulation and return norms of the errors (no plot)
+    sp_err = run_once(false);
+    err = sum(vecnorm(sp_err));
+end
\ No newline at end of file
diff --git a/controls/model/modelParameters.m b/controls/model/modelParameters.m
index afe8eb6e624c655a1b3a0336d1b87ce3f92c560d..30bda9a41410236868c9e04b964bc3b692c655b6 100644
--- a/controls/model/modelParameters.m
+++ b/controls/model/modelParameters.m
@@ -1,3 +1,6 @@
+% Contains all the measurable parameters of the quadrotor. Must be run
+% before running the simulation or any other functions in this directory
+
 % Add Library Blocks and 3D animation to Path
     path_1 = genpath('Library_blocks');
     path_2 = genpath('3D_Animation');
@@ -11,7 +14,7 @@
 
 % Define Simulink Runtime (if logAnalysisToggle is selected, this will be
 % automatically set based on the log files time)
-     runtime = 40;%max(time);
+     runtime = 40;
     
 % Model Parameters
     m = 1.216;                          % Quadrotor + battery mass
@@ -63,7 +66,7 @@
     OF_Fc = 7;
     OF_K = tan(pi * OF_Fc / Fs);
     
-     OF_norm = 1.0 / (1.0 + OF_K/Q + OF_K*OF_K);
+    OF_norm = 1.0 / (1.0 + OF_K/Q + OF_K*OF_K);
     
     OF_b0 = OF_K*OF_K*OF_norm;
     OF_b1 = 2.0*OF_b0;
@@ -243,135 +246,142 @@ if logAnalysisToggle == 1
     % Pull VRPN pitch and roll
     pitch_measured_VRPN = dataStruct.Pitch_trim_add_Sum.data;
     
-   
     % Define setpoint timeseries
     x_setpoint_model = timeseries(x_setpoint, time);
     y_setpoint_model = timeseries(y_setpoint, time);
     z_setpoint_model = timeseries(z_setpoint, time);
-    
 end
 
 if physicsVerificationToggle == 1
-   % PHYSICAL SYSTEM PARAMETERS
-
-% quadrotor + battery mass
-m = 1.216; 
-% quadrotor + battery inertia tensor
-J = diag([ 0.0130 0.0140 0.0285 ]);
-% quadrotor + battery body frame origin to c.o.g. error radius
-r_oc = [ 0 ; 0 ; 0 ]; 
-
-% mass of rigidly attached load
-m_L = 0;
-% dimensions of assuemd rectangular load
-x_L = 0; y_L = 0; z_L = 0; 
-x_L = 0; y_L = 0; z_L = 0; 
-% inertia tensor of load
-J_L = m_L/12*diag([y_L^2+z_L^2,x_L^2+z_L^2,x_L^2+y_L^2]);
-% location of load center of mass in body frame
-r_oL = [0; 0; 0];%[ 0.12 ; 0.12 ; -0.04];%(0.04 + z_L/2) ]; 
-%r_oL = [ .115 ; .115 ; 0.04]; 
-
-% acceleration of gravity 
-g = 9.81; 
-
-% initial dynamics states conditions 
-u0 = 0; 
-v0 = 0; 
-w0 = 0; 
-p0 = 0; 
-q0 = 0; 
-r0 = 0; 
-x0 = 0; 
-y0 = 0; 
-z0 = 0; 
-phi0 = 0; 
-theta0 = 0; 
-psi0 = 0; 
-
-% ROTOR PARAMETERS
-
-% nominally equal rotor parameters
-K_T = cell(1,4); K_H = cell(1,4); K_d = cell(1,4); 
-Delta_T = cell(1,4); 
-%Delta_T = [0 0 0];
-J_r = cell(1,4); Gamma_H = cell(1,4); 
-for i = 1:4
-	% rotor thrust constants
-	K_T{i} = 1.2007e-05; 
-	% rotor H-force coefficeint
-	K_H{i} = 3.4574e-04; 
-	% rotor drag constant
-	K_d{i} = 1.4852e-07;
-	% rotor b_z axis velocity thrust adjustment factor 
-	Delta_T{i} = 0.5*[ 0 0 2.351e-4 ]; 
-	% equivalent rotor + motor moment of inertia 
-	J_r{i} = 4.2012e-05;
-    % h-force xy-plane selection matrix
-    Gamma_H{i} = [ 1 0 0 ; 0 1 0 ; 0 0 0 ]; 
-end
-
-
-
-% ESC-MOTOR PARAMETERS 
-have_motor_transient = 1;  
-% nominally equal motor and eletronic speed control parameters
-R_m = cell(1,4); K_Q = cell(1,4); K_V = cell(1,4); 
-i_0 = cell(1,4); omega_0 = cell(1,4); K_E = cell(1,4); 
-p_0 = cell(1,4); p_max = cell(1,4); 
-for i = 1:4
-	% motor resistance
-	R_m{i} = 0.235; 
-	% motor torque constant
-	K_Q{i} = 96.3422; 
-	% motor back-emf constant
-	K_V{i} = 96.3422; 
-	% motor no-load current 
-	i_0{i} = 0.3836; 
-	% initial motor/rotor speed
-	omega_0{i} = (m*g/4/K_T{1})^0.5;
-	% ESC normalized pwm input factor
-	K_E{i} = 1;
-	% ESC turn-on duty cycle
-	p_0{i} = 0; 
-	% ESC maximum duty cycle (as calibrated)
-	p_max{i} = 1; 
+    % PHYSICAL SYSTEM PARAMETERS
+    % quadrotor + battery inertia tensor
+    J = diag([ Jxx Jyy Jzz ]);
+    % quadrotor + battery body frame origin to c.o.g. error radius
+    r_oc = [ 0 ; 0 ; 0 ]; 
+    
+    % mass of rigidly attached load
+    m_L = 0;
+    % dimensions of assuemd rectangular load
+    x_L = 0; y_L = 0; z_L = 0; 
+    % inertia tensor of load
+    J_L = m_L/12*diag([y_L^2+z_L^2,x_L^2+z_L^2,x_L^2+y_L^2]);
+    % location of load center of mass in body frame
+    r_oL = [0; 0; 0];%[ 0.12 ; 0.12 ; -0.04];%(0.04 + z_L/2) ]; 
+    %r_oL = [ .115 ; .115 ; 0.04]; 
+    
+    % acceleration of gravity 
+    g = 9.81; 
+    
+    % initial dynamics states conditions 
+    u0 = 0; 
+    v0 = 0; 
+    w0 = 0; 
+    p0 = 0; 
+    q0 = 0; 
+    r0 = 0; 
+    x0 = 0; 
+    y0 = 0; 
+    z0 = 0; 
+    phi0 = 0; 
+    theta0 = 0; 
+    psi0 = 0;
+    
+    % ROTOR PARAMETERS
+    
+    % nominally equal rotor parameters
+    K_T = cell(1,4); K_H = cell(1,4); K_d = cell(1,4); 
+    Delta_T = cell(1,4); 
+    %Delta_T = [0 0 0];
+    J_r = cell(1,4); Gamma_H = cell(1,4); 
+    for i = 1:4
+        % rotor thrust constants
+        K_T{i} = Kt;
+        % rotor H-force coefficeint
+        K_H{i} = Kh;
+        % rotor drag constant
+        K_d{i} = Kd;
+        % rotor b_z axis velocity thrust adjustment factor 
+        Delta_T{i} = 0.5*[ 0 0 2.351e-4 ]; 
+        % equivalent rotor + motor moment of inertia 
+        J_r{i} = Jreq;
+        % h-force xy-plane selection matrix
+        Gamma_H{i} = [ 1 0 0 ; 0 1 0 ; 0 0 0 ]; 
+    end
+    
+    % ESC-MOTOR PARAMETERS 
+    have_motor_transient = 1;  
+    % nominally equal motor and eletronic speed control parameters
+    R_m = cell(1,4); K_Q = cell(1,4); K_V = cell(1,4); 
+    i_0 = cell(1,4); omega_0 = cell(1,4); K_E = cell(1,4); 
+    p_0 = cell(1,4); p_max = cell(1,4); 
+    for i = 1:4
+        % motor resistance
+        R_m{i} = 0.235; 
+        % motor torque constant
+        K_Q{i} = 96.3422; 
+        % motor back-emf constant
+        K_V{i} = 96.3422; 
+        % motor no-load current 
+        i_0{i} = 0.3836; 
+        % initial motor/rotor speed
+        omega_0{i} = (m*g/4/K_T{1})^0.5;
+        % ESC normalized pwm input factor
+        K_E{i} = 1;
+        % ESC turn-on duty cycle
+        p_0{i} = 0; 
+        % ESC maximum duty cycle (as calibrated)
+        p_max{i} = 1; 
+    end
+    
+    
+    
+    % ROTOR LOCATION/ORIENTATION PARAMETERS
+    
+    % locatin of hub 1 in body frame
+    r_h{1} = [ rhx ; rhy ; -rhz ]; 
+    % rotor 1 thrust unit vector
+    Gamma_T{1} = [ 0 ; 0 ; -1 ]; 
+    % rotor 1 rotation unit vector
+    Gamma_Omega{1} = [ 0 ; 0 ; -1 ]; 
+    
+    r_h{2} = [ -rhx ; rhy ; -rhz ];
+    Gamma_T{2} = [ 0 ; 0 ; -1 ]; 
+    Gamma_Omega{2} = [ 0 ; 0 ; 1 ]; 
+    
+    r_h{3} = [ -rhx ; -rhy ; -rhz ]; 
+    Gamma_T{3} = [ 0 ; 0 ; -1 ];
+    Gamma_Omega{3} = [ 0 ; 0 ; -1 ];
+    
+    r_h{4} = [ rhx ; -rhy ; -rhz ]; 
+    Gamma_T{4} = [ 0 ; 0 ; -1 ];
+    Gamma_Omega{4} = [ 0 ; 0 ; 1 ]; 
+    
+    
+    
+    % BATTERY PARAMETERS
+    
+    % starting/operating battery voltage
+    V_0 = 11.4; %12.4; %11.4; 
+    % approximate hovering rate of battery discharge
+    d_V = 0; 
+    
+    % DISTURBANCE PARAMETERS
+    
+    F_D = 1*randn(3,1); 
+    Q_D = 0.05*randn(3,1);
 end
 
-
-
-% ROTOR LOCATION/ORIENTATION PARAMETERS
-
-% locatin of hub 1 in body frame
-r_h{1} = [ rhx ; rhy ; -rhz ]; 
-% rotor 1 thrust unit vector
-Gamma_T{1} = [ 0 ; 0 ; -1 ]; 
-% rotor 1 rotation unit vector
-Gamma_Omega{1} = [ 0 ; 0 ; -1 ]; 
-
-r_h{2} = [ -rhx ; rhy ; -rhz ];
-Gamma_T{2} = [ 0 ; 0 ; -1 ]; 
-Gamma_Omega{2} = [ 0 ; 0 ; 1 ]; 
-
-r_h{3} = [ -rhx ; -rhy ; -rhz ]; 
-Gamma_T{3} = [ 0 ; 0 ; -1 ];
-Gamma_Omega{3} = [ 0 ; 0 ; -1 ];
-
-r_h{4} = [ rhx ; -rhy ; -rhz ]; 
-Gamma_T{4} = [ 0 ; 0 ; -1 ];
-Gamma_Omega{4} = [ 0 ; 0 ; 1 ]; 
-
-
-
-% BATTERY PARAMETERS
-
-% starting/operating battery voltage
-V_0 = 11.4; %12.4; %11.4; 
-% approximate hovering rate of battery discharge
-d_V = 0; 
-
-% DISTURBANCE PARAMETERS
-
-F_D = 1*randn(3,1); 
-Q_D = 0.05*randn(3,1);
-end
\ No newline at end of file
+% Signal mixer using rotor layout
+% 1 2
+% 3 4
+signal_mixer = [ 1, -1, -1, -1 
+                 1, -1,  1,  1
+                 1,  1, -1,  1
+                 1,  1,  1, -1 ];
+
+% Linearize model, load preferred weight set, and build LQR model
+[ssA, ssB] = linearization(m, g, Kt, Kh, Kd, delta_T(3), rhx, rhy, rhz, J, Jreq, Vb, Rm, Kv, Kq, If, signal_mixer);
+load('weights_modern.mat');
+% Set control period to equal period of camera system
+T_LQR = Tc;
+[lqr_K, lqr_S, lqr_E] = initial_lqr(ssA, ssB, state_weights, command_weights, T_LQR);
\ No newline at end of file
diff --git a/controls/model/repeated_opt.m b/controls/model/repeated_opt.m
new file mode 100644
index 0000000000000000000000000000000000000000..bc5df87b46af416744e6b8501a6cf1076859e14f
--- /dev/null
+++ b/controls/model/repeated_opt.m
@@ -0,0 +1,29 @@
+% Change the size of the max value in the for loop to change the number of
+% optimizations run. Each run (except the first) picks a random set of LQR
+% weights and uses matlab's fmincon() to repeatedly run the simulation and
+% minimize the value of lqr_err(). The weights resulting weights are stored
+% as .mat files that can be loaded in modelParameters.m.
+
+% Start with weights that look like Matt Rich's values
+rw = matfile('weights_rich.mat');
+sw = double(rw.state_weights); cw = rw.command_weights;
+x0 = [sw([1,3,4,6,7,9,10,12]) cw([1,3,4])];
+for i = 1:30
+    % For other iterations, create random initial weights
+    if (i > 1)
+        x0 = 100*rand(1, 11);
+    end
+    % Run Matlab optimization on weights to minimize simulated error
+    options = optimoptions('fmincon','Display','iter');
+    [X,FVAL,EXITFLAG,OUTPUT] = fmincon(...
+        @(weights) lqr_err(ssA, ssB, weights, T_LQR),...
+        x0, -eye(11), zeros(11, 1), ...
+        [], [], [], [], [], options);
+
+    % Store result of optimization in file
+    state_weights   = X([1, 1:3, 3:5, 5:7, 7:8]);
+    command_weights = X([9:10 10:11]);
+    error_norm = FVAL;
+    fprintf("At timestamp %s, error was %f", datestr(now, 'mmddHHMM'), error_norm);
+    save(['opt_weights_', datestr(now, 'mmddHHMM'), '.mat'], 'state_weights', 'command_weights', 'error_norm');
+end
diff --git a/controls/model/rich_params.m b/controls/model/rich_params.m
new file mode 100644
index 0000000000000000000000000000000000000000..b0e94dbf77820b9e0a803dc4db2518209000d85c
--- /dev/null
+++ b/controls/model/rich_params.m
@@ -0,0 +1,389 @@
+% This file is the same as modelParameters, but the parameter values all
+% match those in Matt Rich's thesis, so the control design or simulation
+% can be run and compared to his results.
+
+% Add Library Blocks and 3D animation to Path
+    path_1 = genpath('Library_blocks');
+    path_2 = genpath('3D_Animation');
+    addpath(path_1, path_2);
+
+% Log Analysis Toggle
+    logAnalysisToggle = 0;          % 1 for log analysis, 0 for normal operation
+   
+% Physics Verification Toggle
+    physicsVerificationToggle = 1;
+
+% Define Simulink Runtime (if logAnalysisToggle is selected, this will be
+% automatically set based on the log files time)
+     runtime = 40;%max(time);
+    
+% Model Parameters
+    m = 0.656;                         % Quadrotor + battery mass
+    g = 9.81;                          % Acceleration of gravity
+    Jxx = 0.0081;                      % Quadrotor and battery motor of inertia around bx (pitch)
+    Jyy = 0.0074;                      % Quadrotor and battery motor of inertia around by (roll)
+    Jzz = 0.0135;                      % Quadrotor and battery motor of inertia around bz (yaw)
+    Jreq = 1.376e-05;                  % Rotor and motor moment of inertia around axis of rotation 
+    Kt = 7.3956e-6;                    % Rotor thrust constant
+    delta_T = [ 0,  0,  1.176e-04 ];   % Thrust constant adjustment factor
+    Kh = 3.4574e-04;                   % Rotor in-plane drag constant
+    Kd = 5.194e-07;                    % Rotor drag constant
+    rhx = 0.115;                       % X-axis distance from center of mass to a rotor hub
+    rhy = 0.115;                       % Y-axis distance from center of mass to a rotor hub
+    rhz = 0.04;                        % Z-axis distance from center of mass to a rotor hub
+    r_oc = [0; 0; 0];                  % Vector from origin to center of mass
+    Rm = 0.19;                         % Motor resistance
+    Kq = 110;                          % Motor torque constant
+    Kv = 110;                          % Motor back emf constant
+    If = 0.39;                         % Motor internal friction current
+    Pmin = 0;                          % Minimum zybo output duty cycle command
+    Pmax = 1;                          % Maximum zybo output duty cycle command
+    Tc = 0.01;%0.04;                   % Camera system sampling period
+    Tq = 0.005;                        % Quad sampling period
+    tau_c = 0;                         % Camera system total latency
+    Vb = 11.4;                         % Nominal battery voltage (V)
+    x_controlled_o = 0;                % Equilibrium lateral controller output
+    y_controlled_o = 0;                % Equilibrium longitudinal controller output
+    yaw_controlled_o = 0;              % Equilibrium yaw controller output
+    Kp_mahony = 0.4;                   % Proportional term for mahony filter
+    Ki_mahony = 0.001;                 % Integral term for mahony filter
+    
+    % Define Biquad Filter Parameters
+    accel_Fc = 10;
+    Fs = 1/Tq;
+    accel_K = tan(pi * accel_Fc / Fs);
+    Q = 0.707;
+    accel_norm = 1.0 / (1.0 + accel_K/Q + accel_K*accel_K);
+    
+    accel_b0 = accel_K*accel_K*accel_norm;
+    accel_b1 = 2.0*accel_b0;
+    accel_b2 = accel_b0;
+    accel_a0 = 1;
+    accel_a1 = 2.0*(accel_K*accel_K -1) * accel_norm;
+    accel_a2 = (1.0 - accel_K/Q + accel_K*accel_K) * accel_norm;
+    
+    accel_SOS_Matrix = [accel_b0, accel_b1, accel_b2, accel_a0, accel_a1, accel_a2];
+    
+    OF_Fc = 7;
+    OF_K = tan(pi * OF_Fc / Fs);
+    
+    OF_norm = 1.0 / (1.0 + OF_K/Q + OF_K*OF_K);
+    
+    OF_b0 = OF_K*OF_K*OF_norm;
+    OF_b1 = 2.0*OF_b0;
+    OF_b2 = OF_b0;
+    OF_a0 = 1;
+    OF_a1 = 2.0*(OF_K*OF_K -1) * OF_norm;
+    OF_a2 = (1.0 - OF_K/Q + OF_K * OF_K) * OF_norm;
+    
+    OF_SOS_Matrix = [OF_b0, OF_b1, OF_b2, OF_a0, OF_a1, OF_a2];
+    
+    % Determine Initial Conditions
+    
+    % Position Initial Conditions
+    x_o = 0;
+    y_o = 0;
+    z_o = 0;
+    
+    % Velocity Initial Conditions
+    x_vel_o = 0;
+    y_vel_o = 0;
+    z_vel_o = 0;
+    
+    % Euler Angle Initial Conditions
+    roll_o = 0;
+    pitch_o = 0;
+    yaw_o = 0;
+    
+    % Euler Rate Initial Conditions
+    rollrate_o = 0;
+    pitchrate_o = 0;
+    yawrate_o = 0;
+    
+    % Equilibrium rotor speeds
+    omega0_o = sqrt((m*g)/(4*Kt));
+    omega1_o = sqrt((m*g)/(4*Kt));
+    omega2_o = sqrt((m*g)/(4*Kt));
+    omega3_o = sqrt((m*g)/(4*Kt));
+    
+    % Equilibrium height controller output
+    height_controlled_o = (((Rm*If   ...
+    + (((omega0_o * 2 * Rm * Kv * Kq ...
+    * Kd + 1)^2) - 1)/(4* Rm*Kv^2*Kq ...
+    * Kd))/Vb)*(Pmax - Pmin) + Pmin);
+       
+if logAnalysisToggle == 1
+    %%%%%% Commented out section until logging is .txt file based %%%%%%
+    % FNAME
+    % if you know the name of the log file that you want to parse, set the it
+    % here only if it is in the working directory. Otherwise, you may leave it
+    % blank. You will be able to choose the file to parse through an explorer
+    % window.
+    %
+    %fname = 'sampleLogFile.txt';  
+    fname = '';
+    fpath = 'C:\Users\Andy\Documents\School\MicroCART\GitRepo\MicroCART_17-18\controls\model\logFiles\';
+    
+    if(isempty(fname))
+        [fname] = uigetfile('.txt','Select log file', fpath);
+    end
+    
+    params.file.name = fname;               % file name only
+    params.file.path = fpath;               % file path only
+    params.file.pathName = [fpath fname];   % file path with file name
+    
+    [dataStruct, headers] = parse_log_model(params.file.pathName);
+    
+    time = dataStruct.Time.data;
+    time = time - time(1);
+    time_indices = length(time);
+    
+    runtime = max(time);
+    
+    % Determine x position error
+    x_setpoint = dataStruct.X_Setpoint_Constant.data;
+    x_pos_raw = dataStruct.VRPN_X_Constant.data;
+    x_error = timeseries(x_setpoint - x_pos_raw, time);
+    x_position = timeseries(x_pos_raw, time);
+
+    % Determine y position error
+    y_setpoint = dataStruct.Y_Setpoint_Constant.data;
+    y_pos_raw = dataStruct.VRPN_Y_Constant.data;
+    y_error = timeseries(y_setpoint - y_pos_raw, time);
+    y_position = timeseries(y_pos_raw, time);
+
+    % Determine z position error
+    z_setpoint = dataStruct.Alt_Setpoint_Constant.data;
+    z_pos_raw = dataStruct.VRPN_Alt_Constant.data;
+    z_error = timeseries(z_setpoint - z_pos_raw, time);
+    z_position = timeseries(z_pos_raw, time);
+    
+    % Determine x velocity error
+    x_vel_setpoint = dataStruct.X_pos_PID_Correction.data;
+    x_vel_raw = dataStruct.X_Vel_Correction.data;
+    x_vel_error = timeseries(x_vel_setpoint - x_vel_raw, time);
+    x_vel = timeseries(x_vel_raw, time);
+    
+    % Determine y velocity error
+    y_vel_setpoint = dataStruct.Y_pos_PID_Correction.data;
+    y_vel_raw = dataStruct.Y_Vel_Correction.data;
+    y_vel_error = timeseries(y_vel_setpoint - y_vel_raw, time);
+    y_vel = timeseries(y_vel_raw, time);
+
+    % Determine pitch error
+    pitch_setpoint = dataStruct.X_Vel_PID_Correction.data;
+    pitch_angle_raw = dataStruct.Pitch_trim_add_Sum.data;
+    pitch_error = timeseries(pitch_setpoint - pitch_angle_raw, time);
+    pitch_angle = timeseries(pitch_angle_raw, time);
+
+    % Determine roll error
+    roll_setpoint = dataStruct.Y_Vel_PID_Correction.data;
+    roll_angle_raw = dataStruct.Roll_Constant.data;
+    roll_error = timeseries(roll_setpoint - roll_angle_raw, time);
+    roll_angle = timeseries(roll_angle_raw, time);
+    
+    % Determine yaw error
+    yaw_setpoint = dataStruct.Yaw_Setpoint_Constant.data;
+    yaw_angle_raw = dataStruct.Yaw_Constant.data;
+    yaw_error = timeseries(yaw_setpoint - yaw_angle_raw, time);
+    yaw_angle = timeseries(yaw_angle_raw, time);
+
+    % Determine pitch rate error
+    pitchrate_setpoint = dataStruct.Pitch_PID_Correction.data;
+    pitchrate_raw = dataStruct.gyro_y.data;
+    pitchrate_error = timeseries(pitchrate_setpoint - pitchrate_raw, time);
+    pitchrate = timeseries(pitchrate_raw, time);
+
+    % Determine roll rate error
+    rollrate_setpoint = dataStruct.Roll_PID_Correction.data;
+    rollrate_raw = dataStruct.gyro_x.data;
+    rollrate_error = timeseries(rollrate_setpoint - rollrate_raw, time);
+    rollrate = timeseries(rollrate_raw, time);
+
+    % Determine yaw rate error
+    yawrate_setpoint = dataStruct.Yaw_PID_Correction.data;
+    yawrate_raw = dataStruct.gyro_z.data;
+    yawrate_error = timeseries(yawrate_setpoint - yawrate_raw, time);
+    yawrate = timeseries(yawrate_raw, time);
+
+    % Pull motor commands from log
+    x_command = dataStruct.Pitch_Rate_PID_Correction.data;
+    y_command = dataStruct.Roll_Rate_PID_Correction.data;
+    z_command = dataStruct.Altitude_PID_Correction.data;
+    yaw_command = dataStruct.Yaw_Rate_PID_Correction.data;
+    
+    % Determine signal mix PWM values
+    PWM0 = dataStruct.Signal_Mixer_MOTOR_0.data;
+    PWM1 = dataStruct.Signal_Mixer_MOTOR_1.data;
+    PWM2 = dataStruct.Signal_Mixer_MOTOR_2.data;
+    PWM3 = dataStruct.Signal_Mixer_MOTOR_3.data;
+    PWM_arr = ...
+        [PWM0, PWM1, PWM2, PWM3];
+    motor_commands = timeseries(PWM_arr, time);
+    
+    % Pull the measurements from the acceleratometer
+    raw_accel_data_x = dataStruct.accel_x.data;
+    raw_accel_data_y = dataStruct.accel_y.data;
+    raw_accel_data_z = dataStruct.accel_z.data;
+    raw_accel_data_arr = ...
+        [ raw_accel_data_x , raw_accel_data_y , raw_accel_data_z ];
+    raw_accel_data = timeseries( raw_accel_data_arr , time );
+    
+    % Pull the measurements from the gyroscope
+    raw_gyro_data_x = dataStruct.gyro_x.data;
+    raw_gyro_data_y = dataStruct.gyro_y.data;
+    raw_gyro_data_z = dataStruct.gyro_z.data;
+    raw_gyro_data_arr = ...
+        [ raw_gyro_data_x , raw_gyro_data_y , raw_gyro_data_z ];
+    raw_gyro_data = timeseries( raw_gyro_data_arr , time );
+        
+    % Pull the measurements from the complimentary filter
+    pitch_measured_IMU = dataStruct.Pitch_trim_add_Sum.data;
+    roll_measured_IMU = dataStruct.Roll_Constant.data;
+    IMU_angle_arr = ...
+        [roll_measured_IMU, pitch_measured_IMU];
+    IMU_angle_data = timeseries( IMU_angle_arr, time);
+    
+    % Pull VRPN pitch and roll
+    pitch_measured_VRPN = dataStruct.Pitch_trim_add_Sum.data;
+    
+   
+    % Define setpoint timeseries
+    x_setpoint_model = timeseries(x_setpoint, time);
+    y_setpoint_model = timeseries(y_setpoint, time);
+    z_setpoint_model = timeseries(z_setpoint, time);
+    
+end
+
+if physicsVerificationToggle == 1
+   % PHYSICAL SYSTEM PARAMETERS
+ 
+% quadrotor + battery inertia tensor
+J = diag([Jxx Jyy Jzz]);
+% quadrotor + battery body frame origin to c.o.g. error radius
+r_oc = [ 0 ; 0 ; 0 ]; 
+
+% mass of rigidly attached load
+m_L = 0;
+% dimensions of assuemd rectangular load
+x_L = 0; y_L = 0; z_L = 0; 
+x_L = 0; y_L = 0; z_L = 0; 
+% inertia tensor of load
+J_L = m_L/12*diag([y_L^2+z_L^2,x_L^2+z_L^2,x_L^2+y_L^2]);
+% location of load center of mass in body frame
+r_oL = [0; 0; 0];%[ 0.12 ; 0.12 ; -0.04];%(0.04 + z_L/2) ]; 
+%r_oL = [ .115 ; .115 ; 0.04]; 
+
+% acceleration of gravity 
+g = 9.81; 
+
+% initial dynamics states conditions 
+u0 = 0; 
+v0 = 0; 
+w0 = 0; 
+p0 = 0; 
+q0 = 0; 
+r0 = 0; 
+x0 = 0; 
+y0 = 0; 
+z0 = 0; 
+phi0 = 0; 
+theta0 = 0; 
+psi0 = 0; 
+
+% ROTOR PARAMETERS
+
+% nominally equal rotor parameters
+K_T = cell(1,4); K_H = cell(1,4); K_d = cell(1,4); 
+Delta_T = cell(1,4); 
+%Delta_T = [0 0 0];
+J_r = cell(1,4); Gamma_H = cell(1,4); 
+for i = 1:4
+	% rotor thrust constants
+	K_T{i} = Kt; 
+	% rotor H-force coefficeint
+	K_H{i} = Kh; 
+	% rotor drag constant
+	K_d{i} = Kd;
+	% rotor b_z axis velocity thrust adjustment factor 
+	Delta_T{i} = .125 * delta_T; 
+	% equivalent rotor + motor moment of inertia 
+	J_r{i} = Jreq;
+    % h-force xy-plane selection matrix
+    Gamma_H{i} = [ 1 0 0 ; 0 1 0 ; 0 0 0 ]; 
+end
+
+
+
+% ESC-MOTOR PARAMETERS 
+have_motor_transient = 1;  
+% nominally equal motor and eletronic speed control parameters
+R_m = cell(1,4); K_Q = cell(1,4); K_V = cell(1,4); 
+i_0 = cell(1,4); omega_0 = cell(1,4); K_E = cell(1,4); 
+p_0 = cell(1,4); p_max = cell(1,4); 
+for i = 1:4
+	% motor resistance
+	R_m{i} = Rm; 
+	% motor torque constant
+	K_Q{i} = Kq; 
+	% motor back-emf constant
+	K_V{i} = Kv; 
+	% motor no-load current 
+	i_0{i} = If; 
+	% initial motor/rotor speed
+	omega_0{i} = (m*g/4/K_T{1})^0.5;
+	% ESC normalized pwm input factor
+	K_E{i} = 1;
+	% ESC turn-on duty cycle
+	p_0{i} = 0; 
+	% ESC maximum duty cycle (as calibrated)
+	p_max{i} = 1; 
+end
+
+
+
+% ROTOR LOCATION/ORIENTATION PARAMETERS
+
+% locatin of hub 1 in body frame
+r_h{1} = [ rhx ; rhy ; -rhz ]; 
+% rotor 1 thrust unit vector
+Gamma_T{1} = [ 0 ; 0 ; -1 ]; 
+% rotor 1 rotation unit vector
+Gamma_Omega{1} = [ 0 ; 0 ; -1 ]; 
+
+r_h{2} = [ -rhx ; rhy ; -rhz ];
+Gamma_T{2} = [ 0 ; 0 ; -1 ]; 
+Gamma_Omega{2} = [ 0 ; 0 ; 1 ]; 
+
+r_h{3} = [ -rhx ; -rhy ; -rhz ]; 
+Gamma_T{3} = [ 0 ; 0 ; -1 ];
+Gamma_Omega{3} = [ 0 ; 0 ; -1 ];
+
+r_h{4} = [ rhx ; -rhy ; -rhz ]; 
+Gamma_T{4} = [ 0 ; 0 ; -1 ];
+Gamma_Omega{4} = [ 0 ; 0 ; 1 ]; 
+
+
+
+% BATTERY PARAMETERS
+
+% starting/operating battery voltage
+V_0 = 11.4; %12.4; %11.4; 
+% approximate hovering rate of battery discharge
+d_V = 0; 
+
+% DISTURBANCE PARAMETERS
+
+F_D = 1*randn(3,1); 
+Q_D = 0.05*randn(3,1);
+end
+
+signal_mixer = [ 1, -1, -1, -1 
+                 1, -1,  1,  1
+                 1,  1, -1,  1
+                 1,  1,  1, -1 ];
+
+% System linearization and lqr construction             
+[ssA, ssB] = linearization(m, g, Kt, Kh, Kd, delta_T(3), rhx, rhy, rhz, J, Jreq, Vb, Rm, Kv, Kq, If, signal_mixer);
+load('weights_rich.mat');
+[lqr_K, lqr_S, lqr_E] = initial_lqr(ssA, ssB, state_weights, command_weights, .01);
diff --git a/controls/model/run_once.m b/controls/model/run_once.m
new file mode 100644
index 0000000000000000000000000000000000000000..e90667285f030ccb3a5999f06476ef1f01eac1e8
--- /dev/null
+++ b/controls/model/run_once.m
@@ -0,0 +1,33 @@
+% Runs the simulation once, optionally plotting the setpoint errors
+function [sp_err] = run_once(show_plot)
+    output = sim('Quadcopter_Model', 'ReturnWorkspaceOutputs','on');
+    % Use position errors but not velocity
+    sp_err    = output.yout{1}.Values.Data(:, (7:12));
+    setpoints = output.yout{2}.Values.Data;
+    position  = [output.yout{3}.Values.Data output.yout{4}.Values.Data(:,3)];
+    
+    % Plot position and angle error
+    if show_plot
+        close all;
+        % Separate position and angle errors
+        position_err = sp_err(:, 1:3);
+        angle_err = sp_err(:,4:6);
+        time = output.tout;
+        
+        % Draw plots of errors 
+        figure; hold on; 
+        plot(time, position_err); plot(time, angle_err, '-.');
+        title('Position and Euler Angle Error');
+        xlabel('Time (s)'); ylabel('Error (m or rad)');
+        legend({'x', 'y', 'z', '\phi', '\theta', '\psi'});
+        hold off;
+        
+        % Plot position and setpoints
+        figure; hold on; 
+        plot(time, position); plot(time, setpoints, '-.');
+        title('Setpoints and Actual Position');
+        xlabel('Time (s)'); ylabel('Value (m or rad)');
+        legend({'x', 'y', 'z', '\psi'});
+        hold off;
+    end
+end
\ No newline at end of file
diff --git a/controls/model/test_improved_lqr.m b/controls/model/test_improved_lqr.m
new file mode 100644
index 0000000000000000000000000000000000000000..33ef15eddffc046be30ed7d39afd33adba72d7d3
--- /dev/null
+++ b/controls/model/test_improved_lqr.m
@@ -0,0 +1,4 @@
+[lqr_K, lqr_S, lqr_E] = improved_lqr(ssA, ssB,...
+    [1,0;0,sqrt(10);0,0], [.5, 1/.6, 1/25, 1/.25], [1,0;0,sqrt(10);0,0],...
+    [0;0;1/50], 1/60, [0;0;1/50],...
+    .01);
\ No newline at end of file
diff --git a/controls/model/test_model.slx b/controls/model/test_model.slx
deleted file mode 100644
index 35a8b396d018cd92f55e5327af5b488dbafddcaf..0000000000000000000000000000000000000000
Binary files a/controls/model/test_model.slx and /dev/null differ
diff --git a/controls/model/test_model_R2015A.mdl b/controls/model/test_model_R2015A.mdl
deleted file mode 100644
index ce48e8a27d8d691a51c7680ee7430230795f463d..0000000000000000000000000000000000000000
--- a/controls/model/test_model_R2015A.mdl
+++ /dev/null
@@ -1,12432 +0,0 @@
-Model {
-  Name			  "test_model_R2015A"
-  Version		  8.5
-  MdlSubVersion		  0
-  SavedCharacterEncoding  "windows-1252"
-  GraphicalInterface {
-    NumRootInports	    0
-    NumRootOutports	    0
-    ParameterArgumentNames  ""
-    ComputedModelVersion    "1.2002"
-    NumModelReferences	    0
-    NumTestPointedSignals   0
-  }
-  ScopeRefreshTime	  0.035000
-  OverrideScopeRefreshTime off
-  DisableAllScopes	  off
-  DataTypeOverride	  "UseLocalSettings"
-  DataTypeOverrideAppliesTo "AllNumericTypes"
-  MinMaxOverflowLogging	  "UseLocalSettings"
-  MinMaxOverflowArchiveMode "Overwrite"
-  FPTRunName		  "Run 1"
-  MaxMDLFileLineLength	  120
-  Object {
-    $PropName		    "BdWindowsInfo"
-    $ObjectID		    1
-    $ClassName		    "Simulink.BDWindowsInfo"
-    Object {
-      $PropName		      "WindowsInfo"
-      $ObjectID		      2
-      $ClassName	      "Simulink.WindowInfo"
-      IsActive		      [1]
-      Location		      [69.0, 48.0, 1743.0, 940.0]
-      Object {
-	$PropName		"ModelBrowserInfo"
-	$ObjectID		3
-	$ClassName		"Simulink.ModelBrowserInfo"
-	Visible			[0]
-	DockPosition		"Left"
-	Width			[50]
-	Height			[50]
-	Filter			[9]
-      }
-      Object {
-	$PropName		"ExplorerBarInfo"
-	$ObjectID		4
-	$ClassName		"Simulink.ExplorerBarInfo"
-	Visible			[1]
-      }
-      Array {
-	Type			"Simulink.EditorInfo"
-	Dimension		2
-	Object {
-	  $ObjectID		  5
-	  IsActive		  [1]
-	  ViewObjType		  "SimulinkTopLevel"
-	  LoadSaveID		  "0"
-	  Extents		  [1693.0, 762.0]
-	  ZoomFactor		  [1.25]
-	  Offset		  [113.60000000000002, 92.0]
-	}
-	Object {
-	  $ObjectID		  6
-	  IsActive		  [0]
-	  ViewObjType		  "SimulinkSubsys"
-	  LoadSaveID		  "658"
-	  Extents		  [1693.0, 762.0]
-	  ZoomFactor		  [1.0]
-	  Offset		  [0.0, 0.0]
-	}
-	PropName		"EditorsInfo"
-      }
-    }
-  }
-  Created		  "Thu Nov 03 18:34:52 2016"
-  Creator		  "Andy"
-  UpdateHistory		  "UpdateHistoryNever"
-  ModifiedByFormat	  "%<Auto>"
-  LastModifiedBy	  "m87rich"
-  ModifiedDateFormat	  "%<Auto>"
-  LastModifiedDate	  "Sun Feb 19 17:01:58 2017"
-  RTWModifiedTimeStamp	  409366141
-  ModelVersionFormat	  "1.%<AutoIncrement:2002>"
-  ConfigurationManager	  "none"
-  SampleTimeColors	  on
-  SampleTimeAnnotations	  off
-  LibraryLinkDisplay	  "disabled"
-  WideLines		  off
-  ShowLineDimensions	  on
-  ShowPortDataTypes	  off
-  ShowDesignRanges	  off
-  ShowLoopsOnError	  on
-  IgnoreBidirectionalLines off
-  ShowStorageClass	  off
-  ShowTestPointIcons	  on
-  ShowSignalResolutionIcons on
-  ShowViewerIcons	  on
-  SortedOrder		  off
-  ExecutionContextIcon	  off
-  ShowLinearizationAnnotations on
-  ShowMarkup		  on
-  BlockNameDataTip	  off
-  BlockParametersDataTip  off
-  BlockDescriptionStringDataTip	off
-  ToolBar		  on
-  StatusBar		  on
-  BrowserShowLibraryLinks off
-  BrowserLookUnderMasks	  off
-  SimulationMode	  "normal"
-  PauseTimes		  "5"
-  NumberOfSteps		  1
-  SnapshotBufferSize	  10
-  SnapshotInterval	  10
-  NumberOfLastSnapshots	  0
-  LinearizationMsg	  "none"
-  Profile		  off
-  ParamWorkspaceSource	  "MATLABWorkspace"
-  AccelSystemTargetFile	  "accel.tlc"
-  AccelTemplateMakefile	  "accel_default_tmf"
-  AccelMakeCommand	  "make_rtw"
-  TryForcingSFcnDF	  off
-  Object {
-    $PropName		    "DataLoggingOverride"
-    $ObjectID		    7
-    $ClassName		    "Simulink.SimulationData.ModelLoggingInfo"
-    model_		    "test_model_R2015A"
-    overrideMode_	    [0.0]
-    Array {
-      Type		      "Cell"
-      Dimension		      1
-      Cell		      "test_model_R2015A"
-      PropName		      "logAsSpecifiedByModels_"
-    }
-    Array {
-      Type		      "Cell"
-      Dimension		      1
-      Cell		      []
-      PropName		      "logAsSpecifiedByModelsSSIDs_"
-    }
-  }
-  RecordCoverage	  off
-  CovPath		  "/"
-  CovSaveName		  "covdata"
-  CovMetricSettings	  "dwe"
-  CovNameIncrementing	  off
-  CovHtmlReporting	  off
-  CovForceBlockReductionOff on
-  CovEnableCumulative	  on
-  covSaveCumulativeToWorkspaceVar off
-  CovSaveSingleToWorkspaceVar off
-  CovCumulativeVarName	  "covCumulativeData"
-  CovCumulativeReport	  off
-  CovReportOnPause	  on
-  CovModelRefEnable	  "Off"
-  CovExternalEMLEnable	  on
-  CovSFcnEnable		  on
-  CovBoundaryAbsTol	  0.000010
-  CovBoundaryRelTol	  0.010000
-  CovUseTimeInterval	  off
-  CovStartTime		  0
-  CovStopTime		  0
-  ExtModeBatchMode	  off
-  ExtModeEnableFloating	  on
-  ExtModeTrigType	  "manual"
-  ExtModeTrigMode	  "normal"
-  ExtModeTrigPort	  "1"
-  ExtModeTrigElement	  "any"
-  ExtModeTrigDuration	  1000
-  ExtModeTrigDurationFloating "auto"
-  ExtModeTrigHoldOff	  0
-  ExtModeTrigDelay	  0
-  ExtModeTrigDirection	  "rising"
-  ExtModeTrigLevel	  0
-  ExtModeArchiveMode	  "off"
-  ExtModeAutoIncOneShot	  off
-  ExtModeIncDirWhenArm	  off
-  ExtModeAddSuffixToVar	  off
-  ExtModeWriteAllDataToWs off
-  ExtModeArmWhenConnect	  on
-  ExtModeSkipDownloadWhenConnect off
-  ExtModeLogAll		  on
-  ExtModeAutoUpdateStatusClock on
-  ShowModelReferenceBlockVersion off
-  ShowModelReferenceBlockIO off
-  Array {
-    Type		    "Handle"
-    Dimension		    1
-    Simulink.ConfigSet {
-      $ObjectID		      8
-      Version		      "1.15.0"
-      Array {
-	Type			"Handle"
-	Dimension		8
-	Simulink.SolverCC {
-	  $ObjectID		  9
-	  Version		  "1.15.0"
-	  StartTime		  "0.0"
-	  StopTime		  "20"
-	  AbsTol		  "auto"
-	  FixedStep		  "auto"
-	  InitialStep		  "auto"
-	  MaxNumMinSteps	  "-1"
-	  MaxOrder		  5
-	  ZcThreshold		  "auto"
-	  ConsecutiveZCsStepRelTol "10*128*eps"
-	  MaxConsecutiveZCs	  "1000"
-	  ExtrapolationOrder	  4
-	  NumberNewtonIterations  1
-	  MaxStep		  "auto"
-	  MinStep		  "auto"
-	  MaxConsecutiveMinStep	  "1"
-	  RelTol		  "1e-3"
-	  SolverMode		  "SingleTasking"
-	  EnableConcurrentExecution off
-	  ConcurrentTasks	  off
-	  Solver		  "ode45"
-	  SolverName		  "ode45"
-	  SolverJacobianMethodControl "auto"
-	  ShapePreserveControl	  "DisableAll"
-	  ZeroCrossControl	  "UseLocalSettings"
-	  ZeroCrossAlgorithm	  "Nonadaptive"
-	  AlgebraicLoopSolver	  "TrustRegion"
-	  SolverResetMethod	  "Fast"
-	  PositivePriorityOrder	  off
-	  AutoInsertRateTranBlk	  off
-	  SampleTimeConstraint	  "Unconstrained"
-	  InsertRTBMode		  "Whenever possible"
-	}
-	Simulink.DataIOCC {
-	  $ObjectID		  10
-	  Version		  "1.15.0"
-	  Decimation		  "1"
-	  ExternalInput		  "[t, u]"
-	  FinalStateName	  "xFinal"
-	  InitialState		  "xInitial"
-	  LimitDataPoints	  off
-	  MaxDataPoints		  "1000"
-	  LoadExternalInput	  off
-	  LoadInitialState	  off
-	  SaveFinalState	  off
-	  SaveCompleteFinalSimState off
-	  SaveFormat		  "Dataset"
-	  SignalLoggingSaveFormat "Dataset"
-	  SaveOutput		  on
-	  SaveState		  off
-	  SignalLogging		  on
-	  DSMLogging		  on
-	  InspectSignalLogs	  off
-	  VisualizeSimOutput	  on
-	  SaveTime		  on
-	  ReturnWorkspaceOutputs  off
-	  StateSaveName		  "xout"
-	  TimeSaveName		  "tout"
-	  OutputSaveName	  "yout"
-	  SignalLoggingName	  "logsout"
-	  DSMLoggingName	  "dsmout"
-	  OutputOption		  "RefineOutputTimes"
-	  OutputTimes		  "[]"
-	  ReturnWorkspaceOutputsName "out"
-	  Refine		  "1"
-	}
-	Simulink.OptimizationCC {
-	  $ObjectID		  11
-	  Version		  "1.15.0"
-	  Array {
-	    Type		    "Cell"
-	    Dimension		    8
-	    Cell		    "BooleansAsBitfields"
-	    Cell		    "PassReuseOutputArgsAs"
-	    Cell		    "PassReuseOutputArgsThreshold"
-	    Cell		    "ZeroExternalMemoryAtStartup"
-	    Cell		    "ZeroInternalMemoryAtStartup"
-	    Cell		    "OptimizeModelRefInitCode"
-	    Cell		    "NoFixptDivByZeroProtection"
-	    Cell		    "UseSpecifiedMinMax"
-	    PropName		    "DisabledProps"
-	  }
-	  BlockReduction	  on
-	  BooleanDataType	  on
-	  ConditionallyExecuteInputs on
-	  InlineParams		  off
-	  UseDivisionForNetSlopeComputation "off"
-	  UseFloatMulNetSlope	  off
-	  DefaultUnderspecifiedDataType	"double"
-	  UseSpecifiedMinMax	  off
-	  InlineInvariantSignals  off
-	  OptimizeBlockIOStorage  on
-	  BufferReuse		  on
-	  EnhancedBackFolding	  off
-	  CachingGlobalReferences off
-	  GlobalBufferReuse	  on
-	  StrengthReduction	  off
-	  ExpressionFolding	  on
-	  BooleansAsBitfields	  off
-	  BitfieldContainerType	  "uint_T"
-	  EnableMemcpy		  on
-	  MemcpyThreshold	  64
-	  PassReuseOutputArgsAs	  "Structure reference"
-	  PassReuseOutputArgsThreshold 12
-	  ExpressionDepthLimit	  128
-	  LocalBlockOutputs	  on
-	  RollThreshold		  5
-	  StateBitsets		  off
-	  DataBitsets		  off
-	  ActiveStateOutputEnumStorageType "Native Integer"
-	  ZeroExternalMemoryAtStartup on
-	  ZeroInternalMemoryAtStartup on
-	  InitFltsAndDblsToZero	  off
-	  NoFixptDivByZeroProtection off
-	  EfficientFloat2IntCast  off
-	  EfficientMapNaN2IntZero on
-	  OptimizeModelRefInitCode off
-	  LifeSpan		  "inf"
-	  MaxStackSize		  "Inherit from target"
-	  BufferReusableBoundary  on
-	  SimCompilerOptimization "off"
-	  AccelVerboseBuild	  off
-	}
-	Simulink.DebuggingCC {
-	  $ObjectID		  12
-	  Version		  "1.15.0"
-	  RTPrefix		  "error"
-	  ConsistencyChecking	  "none"
-	  ArrayBoundsChecking	  "none"
-	  SignalInfNanChecking	  "none"
-	  SignalRangeChecking	  "none"
-	  ReadBeforeWriteMsg	  "UseLocalSettings"
-	  WriteAfterWriteMsg	  "UseLocalSettings"
-	  WriteAfterReadMsg	  "UseLocalSettings"
-	  AlgebraicLoopMsg	  "error"
-	  ArtificialAlgebraicLoopMsg "warning"
-	  SaveWithDisabledLinksMsg "warning"
-	  SaveWithParameterizedLinksMsg	"warning"
-	  CheckSSInitialOutputMsg on
-	  UnderspecifiedInitializationDetection	"Simplified"
-	  MergeDetectMultiDrivingBlocksExec "error"
-	  CheckExecutionContextPreStartOutputMsg off
-	  CheckExecutionContextRuntimeOutputMsg	off
-	  SignalResolutionControl "UseLocalSettings"
-	  BlockPriorityViolationMsg "warning"
-	  MinStepSizeMsg	  "warning"
-	  TimeAdjustmentMsg	  "none"
-	  MaxConsecutiveZCsMsg	  "error"
-	  MaskedZcDiagnostic	  "warning"
-	  IgnoredZcDiagnostic	  "warning"
-	  SolverPrmCheckMsg	  "none"
-	  InheritedTsInSrcMsg	  "warning"
-	  DiscreteInheritContinuousMsg "warning"
-	  MultiTaskDSMMsg	  "error"
-	  MultiTaskCondExecSysMsg "error"
-	  MultiTaskRateTransMsg	  "error"
-	  SingleTaskRateTransMsg  "none"
-	  TasksWithSamePriorityMsg "warning"
-	  SigSpecEnsureSampleTimeMsg "warning"
-	  CheckMatrixSingularityMsg "none"
-	  IntegerOverflowMsg	  "warning"
-	  Int32ToFloatConvMsg	  "warning"
-	  ParameterDowncastMsg	  "error"
-	  ParameterOverflowMsg	  "error"
-	  ParameterUnderflowMsg	  "none"
-	  ParameterPrecisionLossMsg "warning"
-	  ParameterTunabilityLossMsg "warning"
-	  FixptConstUnderflowMsg  "none"
-	  FixptConstOverflowMsg	  "none"
-	  FixptConstPrecisionLossMsg "none"
-	  UnderSpecifiedDataTypeMsg "none"
-	  UnnecessaryDatatypeConvMsg "none"
-	  VectorMatrixConversionMsg "none"
-	  InvalidFcnCallConnMsg	  "error"
-	  FcnCallInpInsideContextMsg "EnableAllAsError"
-	  SignalLabelMismatchMsg  "none"
-	  UnconnectedInputMsg	  "warning"
-	  UnconnectedOutputMsg	  "warning"
-	  UnconnectedLineMsg	  "warning"
-	  SFcnCompatibilityMsg	  "none"
-	  FrameProcessingCompatibilityMsg "error"
-	  UniqueDataStoreMsg	  "none"
-	  BusObjectLabelMismatch  "warning"
-	  RootOutportRequireBusObject "warning"
-	  AssertControl		  "UseLocalSettings"
-	  ModelReferenceIOMsg	  "none"
-	  ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error"
-	  ModelReferenceVersionMismatchMessage "none"
-	  ModelReferenceIOMismatchMessage "none"
-	  UnknownTsInhSupMsg	  "warning"
-	  ModelReferenceDataLoggingMessage "warning"
-	  ModelReferenceSymbolNameMessage "warning"
-	  ModelReferenceExtraNoncontSigs "error"
-	  StateNameClashWarn	  "none"
-	  SimStateInterfaceChecksumMismatchMsg "warning"
-	  SimStateOlderReleaseMsg "error"
-	  InitInArrayFormatMsg	  "warning"
-	  StrictBusMsg		  "ErrorLevel1"
-	  BusNameAdapt		  "WarnAndRepair"
-	  NonBusSignalsTreatedAsBus "none"
-	  BlockIODiagnostic	  "none"
-	  SFUnusedDataAndEventsDiag "warning"
-	  SFUnexpectedBacktrackingDiag "error"
-	  SFInvalidInputDataAccessInChartInitDiag "warning"
-	  SFNoUnconditionalDefaultTransitionDiag "error"
-	  SFTransitionOutsideNaturalParentDiag "warning"
-	  SFUnconditionalTransitionShadowingDiag "warning"
-	  SFUndirectedBroadcastEventsDiag "warning"
-	  SFTransitionActionBeforeConditionDiag	"warning"
-	  SFOutputUsedAsStateInMooreChartDiag "error"
-	  IntegerSaturationMsg	  "warning"
-	}
-	Simulink.HardwareCC {
-	  $ObjectID		  13
-	  Version		  "1.15.0"
-	  ProdBitPerChar	  8
-	  ProdBitPerShort	  16
-	  ProdBitPerInt		  32
-	  ProdBitPerLong	  32
-	  ProdBitPerLongLong	  64
-	  ProdBitPerFloat	  32
-	  ProdBitPerDouble	  64
-	  ProdBitPerPointer	  64
-	  ProdLargestAtomicInteger "Char"
-	  ProdLargestAtomicFloat  "Float"
-	  ProdIntDivRoundTo	  "Zero"
-	  ProdEndianess		  "LittleEndian"
-	  ProdWordSize		  32
-	  ProdShiftRightIntArith  on
-	  ProdLongLongMode	  off
-	  ProdHWDeviceType	  "Specified"
-	  TargetBitPerChar	  8
-	  TargetBitPerShort	  16
-	  TargetBitPerInt	  32
-	  TargetBitPerLong	  32
-	  TargetBitPerLongLong	  64
-	  TargetBitPerFloat	  32
-	  TargetBitPerDouble	  64
-	  TargetBitPerPointer	  32
-	  TargetLargestAtomicInteger "Char"
-	  TargetLargestAtomicFloat "None"
-	  TargetShiftRightIntArith on
-	  TargetLongLongMode	  off
-	  TargetIntDivRoundTo	  "Undefined"
-	  TargetEndianess	  "Unspecified"
-	  TargetWordSize	  32
-	  TargetPreprocMaxBitsSint 32
-	  TargetPreprocMaxBitsUint 32
-	  TargetHWDeviceType	  "Specified"
-	  TargetUnknown		  off
-	  ProdEqTarget		  on
-	}
-	Simulink.ModelReferenceCC {
-	  $ObjectID		  14
-	  Version		  "1.15.0"
-	  UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange"
-	  CheckModelReferenceTargetMessage "error"
-	  EnableParallelModelReferenceBuilds off
-	  ParallelModelReferenceErrorOnInvalidPool on
-	  ParallelModelReferenceMATLABWorkerInit "None"
-	  ModelReferenceNumInstancesAllowed "Multi"
-	  PropagateVarSize	  "Infer from blocks in model"
-	  ModelReferencePassRootInputsByReference on
-	  ModelReferenceMinAlgLoopOccurrences off
-	  PropagateSignalLabelsOutOfModel on
-	  SupportModelReferenceSimTargetCustomCode off
-	}
-	Simulink.SFSimCC {
-	  $ObjectID		  15
-	  Version		  "1.15.0"
-	  SFSimOverflowDetection  on
-	  SFSimEcho		  on
-	  SimCtrlC		  on
-	  SimIntegrity		  on
-	  SimUseLocalCustomCode	  off
-	  SimParseCustomCode	  on
-	  SimBuildMode		  "sf_incremental_build"
-	  SimGenImportedTypeDefs  off
-	}
-	Simulink.RTWCC {
-	  $BackupClass		  "Simulink.RTWCC"
-	  $ObjectID		  16
-	  Version		  "1.15.0"
-	  Array {
-	    Type		    "Cell"
-	    Dimension		    13
-	    Cell		    "IncludeHyperlinkInReport"
-	    Cell		    "GenerateTraceInfo"
-	    Cell		    "GenerateTraceReport"
-	    Cell		    "GenerateTraceReportSl"
-	    Cell		    "GenerateTraceReportSf"
-	    Cell		    "GenerateTraceReportEml"
-	    Cell		    "PortableWordSizes"
-	    Cell		    "GenerateWebview"
-	    Cell		    "GenerateCodeMetricsReport"
-	    Cell		    "GenerateCodeReplacementReport"
-	    Cell		    "GenerateMissedCodeReplacementReport"
-	    Cell		    "GenerateErtSFunction"
-	    Cell		    "CreateSILPILBlock"
-	    PropName		    "DisabledProps"
-	  }
-	  SystemTargetFile	  "grt.tlc"
-	  TLCOptions		  ""
-	  GenCodeOnly		  off
-	  MakeCommand		  "make_rtw"
-	  GenerateMakefile	  on
-	  PackageGeneratedCodeAndArtifacts off
-	  PackageName		  ""
-	  TemplateMakefile	  "grt_default_tmf"
-	  PostCodeGenCommand	  ""
-	  Description		  ""
-	  GenerateReport	  off
-	  SaveLog		  off
-	  RTWVerbose		  on
-	  RetainRTWFile		  off
-	  ProfileTLC		  off
-	  TLCDebug		  off
-	  TLCCoverage		  off
-	  TLCAssert		  off
-	  RTWUseLocalCustomCode	  off
-	  RTWUseSimCustomCode	  off
-	  CustomSourceCode	  ""
-	  CustomHeaderCode	  ""
-	  CustomInclude		  ""
-	  CustomSource		  ""
-	  CustomLibrary		  ""
-	  CustomInitializer	  ""
-	  CustomTerminator	  ""
-	  Toolchain		  "Automatically locate an installed toolchain"
-	  BuildConfiguration	  "Faster Builds"
-	  IncludeHyperlinkInReport off
-	  LaunchReport		  off
-	  PortableWordSizes	  off
-	  CreateSILPILBlock	  "None"
-	  CodeExecutionProfiling  off
-	  CodeExecutionProfileVariable "executionProfile"
-	  CodeProfilingSaveOptions "SummaryOnly"
-	  CodeProfilingInstrumentation off
-	  SILDebugging		  off
-	  TargetLang		  "C"
-	  IncludeBusHierarchyInRTWFileBlockHierarchyMap	off
-	  GenerateTraceInfo	  off
-	  GenerateTraceReport	  off
-	  GenerateTraceReportSl	  off
-	  GenerateTraceReportSf	  off
-	  GenerateTraceReportEml  off
-	  GenerateWebview	  off
-	  GenerateCodeMetricsReport off
-	  GenerateCodeReplacementReport	off
-	  GenerateMissedCodeReplacementReport off
-	  RTWCompilerOptimization "off"
-	  RTWCustomCompilerOptimizations ""
-	  CheckMdlBeforeBuild	  "Off"
-	  SharedConstantsCachingThreshold 1024
-	  Array {
-	    Type		    "Handle"
-	    Dimension		    2
-	    Simulink.CodeAppCC {
-	      $ObjectID		      17
-	      Version		      "1.15.0"
-	      Array {
-		Type			"Cell"
-		Dimension		25
-		Cell			"IgnoreCustomStorageClasses"
-		Cell			"IgnoreTestpoints"
-		Cell			"InsertBlockDesc"
-		Cell			"InsertPolySpaceComments"
-		Cell			"SFDataObjDesc"
-		Cell			"MATLABFcnDesc"
-		Cell			"SimulinkDataObjDesc"
-		Cell			"DefineNamingRule"
-		Cell			"SignalNamingRule"
-		Cell			"ParamNamingRule"
-		Cell			"InternalIdentifier"
-		Cell			"InlinedPrmAccess"
-		Cell			"CustomSymbolStr"
-		Cell			"CustomSymbolStrGlobalVar"
-		Cell			"CustomSymbolStrType"
-		Cell			"CustomSymbolStrField"
-		Cell			"CustomSymbolStrFcn"
-		Cell			"CustomSymbolStrModelFcn"
-		Cell			"CustomSymbolStrFcnArg"
-		Cell			"CustomSymbolStrBlkIO"
-		Cell			"CustomSymbolStrTmpVar"
-		Cell			"CustomSymbolStrMacro"
-		Cell			"CustomSymbolStrUtil"
-		Cell			"CustomUserTokenString"
-		Cell			"ReqsInCode"
-		PropName		"DisabledProps"
-	      }
-	      ForceParamTrailComments off
-	      GenerateComments	      on
-	      CommentStyle	      "Auto"
-	      IgnoreCustomStorageClasses on
-	      IgnoreTestpoints	      off
-	      IncHierarchyInIds	      off
-	      MaxIdLength	      31
-	      PreserveName	      off
-	      PreserveNameWithParent  off
-	      ShowEliminatedStatement off
-	      OperatorAnnotations     off
-	      IncAutoGenComments      off
-	      SimulinkDataObjDesc     off
-	      SFDataObjDesc	      off
-	      MATLABFcnDesc	      off
-	      IncDataTypeInIds	      off
-	      MangleLength	      1
-	      CustomSymbolStrGlobalVar "$R$N$M"
-	      CustomSymbolStrType     "$N$R$M_T"
-	      CustomSymbolStrField    "$N$M"
-	      CustomSymbolStrFcn      "$R$N$M$F"
-	      CustomSymbolStrFcnArg   "rt$I$N$M"
-	      CustomSymbolStrBlkIO    "rtb_$N$M"
-	      CustomSymbolStrTmpVar   "$N$M"
-	      CustomSymbolStrMacro    "$R$N$M"
-	      CustomSymbolStrUtil     "$N$C"
-	      DefineNamingRule	      "None"
-	      ParamNamingRule	      "None"
-	      SignalNamingRule	      "None"
-	      InsertBlockDesc	      off
-	      InsertPolySpaceComments off
-	      SimulinkBlockComments   on
-	      MATLABSourceComments    off
-	      EnableCustomComments    off
-	      InternalIdentifier      "Shortened"
-	      InlinedPrmAccess	      "Literals"
-	      ReqsInCode	      off
-	      UseSimReservedNames     off
-	    }
-	    Simulink.GRTTargetCC {
-	      $BackupClass	      "Simulink.TargetCC"
-	      $ObjectID		      18
-	      Version		      "1.15.0"
-	      Array {
-		Type			"Cell"
-		Dimension		15
-		Cell			"IncludeMdlTerminateFcn"
-		Cell			"SuppressErrorStatus"
-		Cell			"ERTCustomFileBanners"
-		Cell			"GenerateSampleERTMain"
-		Cell			"ExistingSharedCode"
-		Cell			"GenerateTestInterfaces"
-		Cell			"ModelStepFunctionPrototypeControlCompliant"
-		Cell			"GenerateAllocFcn"
-		Cell			"PurelyIntegerCode"
-		Cell			"SupportComplex"
-		Cell			"SupportAbsoluteTime"
-		Cell			"SupportContinuousTime"
-		Cell			"SupportNonInlinedSFcns"
-		Cell			"RemoveDisableFunc"
-		Cell			"RemoveResetFunc"
-		PropName		"DisabledProps"
-	      }
-	      TargetFcnLib	      "ansi_tfl_table_tmw.mat"
-	      TargetLibSuffix	      ""
-	      TargetPreCompLibLocation ""
-	      GenFloatMathFcnCalls    "NOT IN USE"
-	      TargetLangStandard      "C99 (ISO)"
-	      CodeReplacementLibrary  "None"
-	      UtilityFuncGeneration   "Auto"
-	      ERTMultiwordTypeDef     "System defined"
-	      ERTMultiwordLength      256
-	      MultiwordLength	      2048
-	      GenerateFullHeader      on
-	      InferredTypesCompatibility off
-	      GenerateSampleERTMain   off
-	      GenerateTestInterfaces  off
-	      ModelReferenceCompliant on
-	      ParMdlRefBuildCompliant on
-	      CompOptLevelCompliant   on
-	      ConcurrentExecutionCompliant on
-	      IncludeMdlTerminateFcn  on
-	      GeneratePreprocessorConditionals "Use local settings"
-	      CombineOutputUpdateFcns on
-	      CombineSignalStateStructs	off
-	      SuppressErrorStatus     off
-	      ERTFirstTimeCompliant   off
-	      IncludeFileDelimiter    "Auto"
-	      ERTCustomFileBanners    off
-	      SupportAbsoluteTime     on
-	      LogVarNameModifier      "rt_"
-	      MatFileLogging	      on
-	      MultiInstanceERTCode    off
-	      CodeInterfacePackaging  "Nonreusable function"
-	      SupportNonFinite	      on
-	      SupportComplex	      on
-	      PurelyIntegerCode	      off
-	      SupportContinuousTime   on
-	      SupportNonInlinedSFcns  on
-	      SupportVariableSizeSignals off
-	      ParenthesesLevel	      "Nominal"
-	      CastingMode	      "Nominal"
-	      MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization"
-	      ModelStepFunctionPrototypeControlCompliant off
-	      CPPClassGenCompliant    on
-	      AutosarCompliant	      off
-	      GRTInterface	      off
-	      GenerateAllocFcn	      off
-	      GenerateSharedConstants on
-	      UseMalloc		      off
-	      ExtMode		      off
-	      ExtModeStaticAlloc      off
-	      ExtModeTesting	      off
-	      ExtModeStaticAllocSize  1000000
-	      ExtModeTransport	      0
-	      ExtModeMexFile	      "ext_comm"
-	      ExtModeIntrfLevel	      "Level1"
-	      RTWCAPISignals	      off
-	      RTWCAPIParams	      off
-	      RTWCAPIStates	      off
-	      RTWCAPIRootIO	      off
-	      GenerateASAP2	      off
-	      MultiInstanceErrorCode  "Error"
-	    }
-	    PropName		    "Components"
-	  }
-	}
-	PropName		"Components"
-      }
-      Name		      "Configuration"
-      CurrentDlgPage	      "Diagnostics"
-      ConfigPrmDlgPosition     [ 195, 142, 1085, 882 ] 
-    }
-    PropName		    "ConfigurationSets"
-  }
-  Simulink.ConfigSet {
-    $PropName		    "ActiveConfigurationSet"
-    $ObjectID		    8
-  }
-  Object {
-    $PropName		    "DataTransfer"
-    $ObjectID		    19
-    $ClassName		    "Simulink.GlobalDataTransfer"
-    DefaultTransitionBetweenSyncTasks "Ensure deterministic transfer (maximum delay)"
-    DefaultTransitionBetweenAsyncTasks "Ensure data integrity only"
-    DefaultTransitionBetweenContTasks "Ensure deterministic transfer (minimum delay)"
-    DefaultExtrapolationMethodBetweenContTasks "None"
-    AutoInsertRateTranBlk   [0]
-  }
-  ExplicitPartitioning	  off
-  BlockDefaults {
-    ForegroundColor	    "black"
-    BackgroundColor	    "white"
-    DropShadow		    off
-    NamePlacement	    "normal"
-    FontName		    "Helvetica"
-    FontSize		    10
-    FontWeight		    "normal"
-    FontAngle		    "normal"
-    ShowName		    on
-    BlockRotation	    0
-    BlockMirror		    off
-  }
-  AnnotationDefaults {
-    HorizontalAlignment	    "center"
-    VerticalAlignment	    "middle"
-    ForegroundColor	    "black"
-    BackgroundColor	    "white"
-    DropShadow		    off
-    FontName		    "Helvetica"
-    FontSize		    10
-    FontWeight		    "normal"
-    FontAngle		    "normal"
-    UseDisplayTextAsClickCallback off
-  }
-  LineDefaults {
-    FontName		    "Helvetica"
-    FontSize		    9
-    FontWeight		    "normal"
-    FontAngle		    "normal"
-  }
-  MaskDefaults {
-    SelfModifiable	    "off"
-    IconFrame		    "on"
-    IconOpaque		    "on"
-    RunInitForIconRedraw    "off"
-    IconRotate		    "none"
-    PortRotate		    "default"
-    IconUnits		    "autoscale"
-  }
-  MaskParameterDefaults {
-    Evaluate		    "on"
-    Tunable		    "on"
-    NeverSave		    "off"
-    Internal		    "off"
-    ReadOnly		    "off"
-    Enabled		    "on"
-    Visible		    "on"
-    ToolTip		    "on"
-  }
-  BlockParameterDefaults {
-    Block {
-      BlockType		      BusCreator
-      Inputs		      "4"
-      DisplayOption	      "none"
-      OutDataTypeStr	      "Inherit: auto"
-      NonVirtualBus	      off
-      InheritFromInputs	      on
-    }
-    Block {
-      BlockType		      BusSelector
-      OutputSignals	      "signal1,signal2,signal3"
-      OutputAsBus	      off
-    }
-    Block {
-      BlockType		      Constant
-      Value		      "1"
-      VectorParams1D	      on
-      SamplingMode	      "Sample based"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Inherit from 'Constant value'"
-      LockScale		      off
-      SampleTime	      "inf"
-      FramePeriod	      "inf"
-      PreserveConstantTs      off
-    }
-    Block {
-      BlockType		      Delay
-      DelayLengthSource	      "Dialog"
-      DelayLength	      "2"
-      DelayLengthUpperLimit   "100"
-      InitialConditionSource  "Dialog"
-      InitialCondition	      "0.0"
-      ExternalReset	      "None"
-      ShowEnablePort	      off
-      PreventDirectFeedthrough off
-      DiagnosticForOutOfRangeDelayLength "None"
-      RemoveProtectionDelayLength off
-      InputProcessing	      "Elements as channels (sample based)"
-      UseCircularBuffer	      off
-      SampleTime	      "-1"
-      StateMustResolveToSignalObject off
-      CodeGenStateStorageClass "Auto"
-    }
-    Block {
-      BlockType		      Demux
-      Outputs		      "4"
-      DisplayOption	      "none"
-      BusSelectionMode	      off
-    }
-    Block {
-      BlockType		      DiscreteIntegrator
-      IntegratorMethod	      "Integration: Forward Euler"
-      gainval		      "1.0"
-      ExternalReset	      "none"
-      InitialConditionSource  "internal"
-      InitialCondition	      "0"
-      InitialConditionSetting "Output"
-      SampleTime	      "1"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	off
-      LimitOutput	      off
-      UpperSaturationLimit    "inf"
-      LowerSaturationLimit    "-inf"
-      ShowSaturationPort      off
-      ShowStatePort	      off
-      IgnoreLimit	      off
-      StateMustResolveToSignalObject off
-      RTWStateStorageClass    "Auto"
-      ICPrevOutput	      "DiscIntNeverNeededParam"
-      ICPrevScaledInput	      "DiscIntNeverNeededParam"
-    }
-    Block {
-      BlockType		      DiscreteTransferFcn
-      NumeratorSource	      "Dialog"
-      Numerator		      "[1]"
-      DenominatorSource	      "Dialog"
-      Denominator	      "[1 0.5]"
-      InitialStatesSource     "Dialog"
-      InitialStates	      "0"
-      InputProcessing	      "Elements as channels (sample based)"
-      ExternalReset	      "None"
-      InitialDenominatorStates "0"
-      FilterStructure	      "Direct form II"
-      SampleTime	      "-1"
-      a0EqualsOne	      off
-      NumCoefMin	      "[]"
-      NumCoefMax	      "[]"
-      DenCoefMin	      "[]"
-      DenCoefMax	      "[]"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      StateDataTypeStr	      "Inherit: Same as input"
-      MultiplicandDataTypeStr "Inherit: Same as input"
-      NumCoefDataTypeStr      "Inherit: Inherit via internal rule"
-      DenCoefDataTypeStr      "Inherit: Inherit via internal rule"
-      NumProductDataTypeStr   "Inherit: Inherit via internal rule"
-      DenProductDataTypeStr   "Inherit: Inherit via internal rule"
-      NumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-      DenAccumDataTypeStr     "Inherit: Inherit via internal rule"
-      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	off
-      StateMustResolveToSignalObject off
-      RTWStateStorageClass    "Auto"
-    }
-    Block {
-      BlockType		      Gain
-      Gain		      "1"
-      Multiplication	      "Element-wise(K.*u)"
-      ParamMin		      "[]"
-      ParamMax		      "[]"
-      ParamDataTypeStr	      "Inherit: Same as input"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Same as input"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	on
-      SampleTime	      "-1"
-    }
-    Block {
-      BlockType		      Ground
-    }
-    Block {
-      BlockType		      Inport
-      Port		      "1"
-      OutputFunctionCall      off
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: auto"
-      LockScale		      off
-      BusOutputAsStruct	      off
-      PortDimensions	      "-1"
-      VarSizeSig	      "Inherit"
-      SampleTime	      "-1"
-      SignalType	      "auto"
-      SamplingMode	      "auto"
-      LatchByDelayingOutsideSignal off
-      LatchInputForFeedbackSignals off
-      Interpolate	      on
-    }
-    Block {
-      BlockType		      Integrator
-      ExternalReset	      "none"
-      InitialConditionSource  "internal"
-      InitialCondition	      "0"
-      LimitOutput	      off
-      UpperSaturationLimit    "inf"
-      LowerSaturationLimit    "-inf"
-      WrapState		      off
-      WrappedStateUpperValue  "pi"
-      WrappedStateLowerValue  "-pi"
-      ShowSaturationPort      off
-      ShowStatePort	      off
-      AbsoluteTolerance	      "auto"
-      IgnoreLimit	      off
-      ZeroCross		      on
-      ContinuousStateAttributes	"''"
-    }
-    Block {
-      BlockType		      Mux
-      Inputs		      "4"
-      DisplayOption	      "none"
-      UseBusObject	      off
-      BusObject		      "BusObject"
-      NonVirtualBus	      off
-    }
-    Block {
-      BlockType		      Outport
-      Port		      "1"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: auto"
-      LockScale		      off
-      BusOutputAsStruct	      off
-      PortDimensions	      "-1"
-      VarSizeSig	      "Inherit"
-      SampleTime	      "-1"
-      SignalType	      "auto"
-      SamplingMode	      "auto"
-      SourceOfInitialOutputValue "Dialog"
-      OutputWhenDisabled      "held"
-      InitialOutput	      "[]"
-    }
-    Block {
-      BlockType		      Quantizer
-      QuantizationInterval    "0.5"
-      LinearizeAsGain	      on
-      SampleTime	      "-1"
-    }
-    Block {
-      BlockType		      RandomNumber
-      Mean		      "0"
-      Variance		      "1"
-      Seed		      "0"
-      SampleTime	      "-1"
-      VectorParams1D	      on
-    }
-    Block {
-      BlockType		      RateTransition
-      Integrity		      on
-      Deterministic	      on
-      X0		      "0"
-      OutPortSampleTimeOpt    "Specify"
-      OutPortSampleTimeMultiple	"1"
-      OutPortSampleTime	      "-1"
-    }
-    Block {
-      BlockType		      S-Function
-      FunctionName	      "system"
-      SFunctionModules	      "''"
-      PortCounts	      "[]"
-      SFunctionDeploymentMode off
-      EnableBusSupport	      off
-    }
-    Block {
-      BlockType		      Saturate
-      UpperLimitSource	      "Dialog"
-      UpperLimit	      "0.5"
-      LowerLimitSource	      "Dialog"
-      LowerLimit	      "-0.5"
-      LinearizeAsGain	      on
-      ZeroCross		      on
-      SampleTime	      "-1"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Same as input"
-      LockScale		      off
-      RndMeth		      "Floor"
-    }
-    Block {
-      BlockType		      Scope
-      ModelBased	      off
-      TickLabels	      "OneTimeTick"
-      ZoomMode		      "on"
-      Grid		      "on"
-      ShowLegends	      off
-      TimeRange		      "auto"
-      YMin		      "-5"
-      YMax		      "5"
-      SaveToWorkspace	      off
-      SaveName		      "ScopeData"
-      DataFormat	      "Array"
-      LimitDataPoints	      on
-      MaxDataPoints	      "5000"
-      Decimation	      "1"
-      SampleInput	      off
-      SampleTime	      "-1"
-      ScrollMode	      off
-    }
-    Block {
-      BlockType		      Step
-      Time		      "1"
-      Before		      "0"
-      After		      "1"
-      SampleTime	      "-1"
-      VectorParams1D	      on
-      ZeroCross		      on
-    }
-    Block {
-      BlockType		      SubSystem
-      ShowPortLabels	      "FromPortIcon"
-      Permissions	      "ReadWrite"
-      PermitHierarchicalResolution "All"
-      TreatAsAtomicUnit	      off
-      MinAlgLoopOccurrences   off
-      PropExecContextOutsideSubsystem off
-      CheckFcnCallInpInsideContextMsg off
-      SystemSampleTime	      "-1"
-      RTWSystemCode	      "Auto"
-      RTWFcnNameOpts	      "Auto"
-      RTWFileNameOpts	      "Auto"
-      FunctionInterfaceSpec   "void_void"
-      FunctionWithSeparateData off
-      RTWMemSecFuncInitTerm   "Inherit from model"
-      RTWMemSecFuncExecute    "Inherit from model"
-      RTWMemSecDataConstants  "Inherit from model"
-      RTWMemSecDataInternal   "Inherit from model"
-      RTWMemSecDataParameters "Inherit from model"
-      SimViewingDevice	      off
-      DataTypeOverride	      "UseLocalSettings"
-      DataTypeOverrideAppliesTo	"AllNumericTypes"
-      MinMaxOverflowLogging   "UseLocalSettings"
-      Opaque		      off
-      MaskHideContents	      off
-      SFBlockType	      "NONE"
-      Variant		      off
-      GeneratePreprocessorConditionals off
-      ContentPreviewEnabled   off
-      IsWebBlock	      off
-    }
-    Block {
-      BlockType		      Sum
-      IconShape		      "rectangular"
-      Inputs		      "++"
-      CollapseMode	      "All dimensions"
-      CollapseDim	      "1"
-      InputSameDT	      on
-      AccumDataTypeStr	      "Inherit: Inherit via internal rule"
-      OutMin		      "[]"
-      OutMax		      "[]"
-      OutDataTypeStr	      "Inherit: Same as first input"
-      LockScale		      off
-      RndMeth		      "Floor"
-      SaturateOnIntegerOverflow	on
-      SampleTime	      "-1"
-    }
-    Block {
-      BlockType		      Terminator
-    }
-    Block {
-      BlockType		      ZeroOrderHold
-      SampleTime	      "1"
-    }
-  }
-  System {
-    Name		    "test_model_R2015A"
-    Location		    [69, 48, 1812, 988]
-    Open		    on
-    ModelBrowserVisibility  off
-    ModelBrowserWidth	    200
-    ScreenColor		    "white"
-    PaperOrientation	    "landscape"
-    PaperPositionMode	    "auto"
-    PaperType		    "usletter"
-    PaperUnits		    "inches"
-    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-    TiledPageScale	    1
-    ShowPageBoundaries	    off
-    ZoomFactor		    "125"
-    ReportName		    "simulink-default.rpt"
-    SIDHighWatermark	    "904"
-    Block {
-      BlockType		      SubSystem
-      Name		      "     Sensors   "
-      SID		      "650"
-      Ports		      [6, 4]
-      Position		      [1195, 272, 1415, 508]
-      ZOrder		      73
-      ForegroundColor	      "yellow"
-      ShowName		      off
-      RequestExecContextInheritance off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		20
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('input', 1, '^{B}Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on');"
-	"\nport_label('input', 3, '^{B}v_o', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmode', 'on');\nport_labe"
-	"l('input', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('input', 6, '^{B}g', 'texmode', 'on');\nport_label('output"
-	"', 1, '\\Theta_{filtered}', 'texmode', 'on');\nport_label('output', 2, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_"
-	"label('output', 3, '^{E}r_o', 'texmode', 'on');\ndisp('Sensors', 'texmode', 'on'); "
-      }
-      System {
-	Name			"     Sensors   "
-	Location		[69, 48, 1812, 988]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"125"
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_Omega"
-	  SID			  "651"
-	  Position		  [1015, 678, 1045, 692]
-	  ZOrder		  265
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "euler_angles"
-	  SID			  "652"
-	  Position		  [1440, 1043, 1470, 1057]
-	  ZOrder		  266
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_vo"
-	  SID			  "653"
-	  Position		  [1015, 613, 1045, 627]
-	  ZOrder		  267
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "E_ro"
-	  SID			  "654"
-	  Position		  [1440, 963, 1470, 977]
-	  ZOrder		  268
-	  Port			  "4"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_vo_dot"
-	  SID			  "655"
-	  Position		  [1015, 548, 1045, 562]
-	  ZOrder		  269
-	  Port			  "5"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "B_g"
-	  SID			  "656"
-	  Position		  [1015, 743, 1045, 757]
-	  ZOrder		  273
-	  Port			  "6"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "3D Graphical Simulation"
-	  SID			  "698"
-	  Ports			  [2]
-	  Position		  [1725, 1075, 1875, 1135]
-	  ZOrder		  287
-	  Commented		  "on"
-	  RequestExecContextInheritance	off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    21
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input',1,'r_{o}','texmode','on')\nport_label('input',2,'\\Theta','texmode','on')"
-	  }
-	  System {
-	    Name		    "3D Graphical Simulation"
-	    Location		    [-8, -8, 1928, 1048]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Displacement"
-	      SID		      "699"
-	      Position		      [110, 218, 140, 232]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Euler Angles"
-	      SID		      "700"
-	      Position		      [125, 108, 155, 122]
-	      ZOrder		      -2
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator"
-	      SID		      "701"
-	      Ports		      [3, 1]
-	      Position		      [600, 76, 610, 154]
-	      ZOrder		      -3
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator1"
-	      SID		      "702"
-	      Ports		      [3, 1]
-	      Position		      [630, 191, 640, 269]
-	      ZOrder		      -4
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator2"
-	      SID		      "703"
-	      Ports		      [3, 1]
-	      Position		      [385, 75, 390, 155]
-	      ZOrder		      -5
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      BusSelector
-	      Name		      "Bus\nSelector"
-	      SID		      "704"
-	      Ports		      [1, 3]
-	      Position		      [500, 77, 505, 153]
-	      ZOrder		      -6
-	      ShowName		      off
-	      OutputSignals	      "phi,theta,psi"
-	      Port {
-		PortNumber		1
-		Name			"<phi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"<theta>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"<psi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux"
-	      SID		      "705"
-	      Ports		      [1, 3]
-	      Position		      [440, 183, 450, 267]
-	      ZOrder		      -7
-	      BackgroundColor	      "black"
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux1"
-	      SID		      "706"
-	      Ports		      [1, 3]
-	      Position		      [290, 75, 295, 155]
-	      ZOrder		      -8
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	      Port {
-		PortNumber		1
-		Name			"phi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"theta"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"psi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain"
-	      SID		      "707"
-	      Position		      [550, 240, 580, 270]
-	      ZOrder		      -10
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain1"
-	      SID		      "708"
-	      Position		      [670, 208, 710, 252]
-	      ZOrder		      -11
-	      Gain		      "eye(3)*1"
-	      Multiplication	      "Matrix(K*u)"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain2"
-	      SID		      "709"
-	      Position		      [550, 190, 580, 220]
-	      ZOrder		      -12
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "MATLAB Function"
-	      SID		      "710"
-	      Ports		      [1, 1]
-	      Position		      [655, 92, 725, 138]
-	      ZOrder		      5
-	      ErrorFcn		      "Stateflow.Translate.translate"
-	      PermitHierarchicalResolution "ExplicitOnly"
-	      TreatAsAtomicUnit	      on
-	      RequestExecContextInheritance off
-	      SFBlockType	      "MATLAB Function"
-	      System {
-		Name			"MATLAB Function"
-		Location		[223, 338, 826, 833]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		SIDHighWatermark	"21"
-		Block {
-		  BlockType		  Inport
-		  Name			  "u"
-		  SID			  "710::1"
-		  Position		  [20, 101, 40, 119]
-		  ZOrder		  -1
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Demux
-		  Name			  " Demux "
-		  SID			  "710::20"
-		  Ports			  [1, 1]
-		  Position		  [270, 230, 320, 270]
-		  ZOrder		  11
-		  Outputs		  "1"
-		}
-		Block {
-		  BlockType		  S-Function
-		  Name			  " SFunction "
-		  SID			  "710::19"
-		  Tag			  "Stateflow S-Function test_model_R2015A 11"
-		  Ports			  [1, 2]
-		  Position		  [180, 100, 230, 160]
-		  ZOrder		  10
-		  FunctionName		  "sf_sfun"
-		  PortCounts		  "[1 2]"
-		  EnableBusSupport	  on
-		  Port {
-		    PortNumber		    2
-		    Name		    "y"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		}
-		Block {
-		  BlockType		  Terminator
-		  Name			  " Terminator "
-		  SID			  "710::21"
-		  Position		  [460, 241, 480, 259]
-		  ZOrder		  12
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "y"
-		  SID			  "710::5"
-		  Position		  [460, 101, 480, 119]
-		  ZOrder		  -5
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "u"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  1
-		}
-		Line {
-		  Name			  "y"
-		  ZOrder		  2
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  2
-		  DstBlock		  "y"
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  3
-		  SrcBlock		  " Demux "
-		  SrcPort		  1
-		  DstBlock		  " Terminator "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  4
-		  SrcBlock		  " SFunction "
-		  SrcPort		  1
-		  DstBlock		  " Demux "
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition"
-	      SID		      "711"
-	      Position		      [755, 94, 795, 136]
-	      ZOrder		      -13
-	      NamePlacement	      "alternate"
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition1"
-	      SID		      "712"
-	      Position		      [735, 210, 770, 250]
-	      ZOrder		      -14
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "VR Sink"
-	      SID		      "713"
-	      Ports		      [2]
-	      Position		      [865, 76, 1055, 234]
-	      ZOrder		      -15
-	      LibraryVersion	      "1.34"
-	      SourceBlock	      "vrlib/VR Sink"
-	      SourceType	      "Virtual Reality Sink"
-	      InstantiateOnLoad	      on
-	      SampleTime	      "-1"
-	      ViewEnable	      on
-	      RemoteChange	      off
-	      RemoteView	      off
-	      FieldsWritten	      "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double"
-	      WorldFileName	      "quadrotor_world_ucart.wrl"
-	      AutoView		      on
-	      VideoDimensions	      "[]"
-	      AllowVariableSize	      off
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "Displacement"
-	      SrcPort		      1
-	      DstBlock		      "Demux"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "Bus\nCreator2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nSelector"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "Demux"
-	      SrcPort		      1
-	      Points		      [40, 0; 0, 40; 120, 0]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "Gain"
-	      SrcPort		      1
-	      Points		      [5, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "Gain2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Rate Transition1"
-	      SrcPort		      1
-	      Points		      [35, 0; 0, -35]
-	      DstBlock		      "VR Sink"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      7
-	      SrcBlock		      "Rate Transition"
-	      SrcPort		      1
-	      DstBlock		      "VR Sink"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "Demux"
-	      SrcPort		      3
-	      DstBlock		      "Gain"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "Demux"
-	      SrcPort		      2
-	      Points		      [80, 0]
-	      DstBlock		      "Gain2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      10
-	      SrcBlock		      "Bus\nCreator1"
-	      SrcPort		      1
-	      DstBlock		      "Gain1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "<phi>"
-	      ZOrder		      11
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      1
-	      Points		      [0, -10; 45, 0; 0, 60]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "<psi>"
-	      ZOrder		      12
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      3
-	      Points		      [0, -10; 75, 0]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "<theta>"
-	      ZOrder		      13
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      2
-	      Points		      [30, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      14
-	      SrcBlock		      "Gain1"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "psi"
-	      ZOrder		      15
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      3
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "theta"
-	      ZOrder		      16
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      2
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "phi"
-	      ZOrder		      17
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "Euler Angles"
-	      SrcPort		      1
-	      DstBlock		      "Demux1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "Bus\nCreator"
-	      SrcPort		      1
-	      DstBlock		      "MATLAB Function"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      20
-	      SrcBlock		      "MATLAB Function"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "3D Graphical Simulation1"
-	  SID			  "714"
-	  Ports			  [2]
-	  Position		  [2635, 815, 2785, 875]
-	  ZOrder		  290
-	  Commented		  "on"
-	  RequestExecContextInheritance	off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    22
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input',1, '\\Theta','texmode','on')\nport_label('input',2,'r_{o}','texmode','on')"
-	  }
-	  System {
-	    Name		    "3D Graphical Simulation1"
-	    Location		    [108, 36, 1850, 976]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Euler Angles\n"
-	      SID		      "715"
-	      Position		      [180, 108, 210, 122]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Displacement"
-	      SID		      "716"
-	      Position		      [180, 218, 210, 232]
-	      ZOrder		      -2
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator"
-	      SID		      "717"
-	      Ports		      [3, 1]
-	      Position		      [600, 76, 610, 154]
-	      ZOrder		      -3
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator1"
-	      SID		      "718"
-	      Ports		      [3, 1]
-	      Position		      [630, 191, 640, 269]
-	      ZOrder		      -4
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      BusCreator
-	      Name		      "Bus\nCreator2"
-	      SID		      "719"
-	      Ports		      [3, 1]
-	      Position		      [385, 75, 390, 155]
-	      ZOrder		      -5
-	      ShowName		      off
-	      Inputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      BusSelector
-	      Name		      "Bus\nSelector"
-	      SID		      "720"
-	      Ports		      [1, 3]
-	      Position		      [500, 77, 505, 153]
-	      ZOrder		      -6
-	      ShowName		      off
-	      OutputSignals	      "phi,theta,psi"
-	      Port {
-		PortNumber		1
-		Name			"<phi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"<theta>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"<psi>"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux"
-	      SID		      "721"
-	      Ports		      [1, 3]
-	      Position		      [440, 183, 450, 267]
-	      ZOrder		      -7
-	      BackgroundColor	      "black"
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      "Demux1"
-	      SID		      "722"
-	      Ports		      [1, 3]
-	      Position		      [290, 75, 295, 155]
-	      ZOrder		      -8
-	      ShowName		      off
-	      Outputs		      "3"
-	      DisplayOption	      "bar"
-	      Port {
-		PortNumber		1
-		Name			"phi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		2
-		Name			"theta"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"psi"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain"
-	      SID		      "723"
-	      Position		      [550, 240, 580, 270]
-	      ZOrder		      -10
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain1"
-	      SID		      "724"
-	      Position		      [670, 208, 710, 252]
-	      ZOrder		      -11
-	      Gain		      "eye(3)*1"
-	      Multiplication	      "Matrix(K*u)"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain2"
-	      SID		      "725"
-	      Position		      [550, 190, 580, 220]
-	      ZOrder		      -12
-	      Gain		      "-1"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "MATLAB Function"
-	      SID		      "726"
-	      Ports		      [1, 1]
-	      Position		      [655, 92, 725, 138]
-	      ZOrder		      5
-	      ErrorFcn		      "Stateflow.Translate.translate"
-	      PermitHierarchicalResolution "ExplicitOnly"
-	      TreatAsAtomicUnit	      on
-	      RequestExecContextInheritance off
-	      SFBlockType	      "MATLAB Function"
-	      System {
-		Name			"MATLAB Function"
-		Location		[223, 338, 826, 833]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		SIDHighWatermark	"21"
-		Block {
-		  BlockType		  Inport
-		  Name			  "u"
-		  SID			  "726::1"
-		  Position		  [20, 101, 40, 119]
-		  ZOrder		  -1
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Demux
-		  Name			  " Demux "
-		  SID			  "726::20"
-		  Ports			  [1, 1]
-		  Position		  [270, 230, 320, 270]
-		  ZOrder		  11
-		  Outputs		  "1"
-		}
-		Block {
-		  BlockType		  S-Function
-		  Name			  " SFunction "
-		  SID			  "726::19"
-		  Tag			  "Stateflow S-Function test_model_R2015A 3"
-		  Ports			  [1, 2]
-		  Position		  [180, 100, 230, 160]
-		  ZOrder		  10
-		  FunctionName		  "sf_sfun"
-		  PortCounts		  "[1 2]"
-		  EnableBusSupport	  on
-		  Port {
-		    PortNumber		    2
-		    Name		    "y"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		}
-		Block {
-		  BlockType		  Terminator
-		  Name			  " Terminator "
-		  SID			  "726::21"
-		  Position		  [460, 241, 480, 259]
-		  ZOrder		  12
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "y"
-		  SID			  "726::5"
-		  Position		  [460, 101, 480, 119]
-		  ZOrder		  -5
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "u"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  1
-		}
-		Line {
-		  Name			  "y"
-		  ZOrder		  2
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  2
-		  DstBlock		  "y"
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  3
-		  SrcBlock		  " Demux "
-		  SrcPort		  1
-		  DstBlock		  " Terminator "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  4
-		  SrcBlock		  " SFunction "
-		  SrcPort		  1
-		  DstBlock		  " Demux "
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition"
-	      SID		      "727"
-	      Position		      [755, 94, 795, 136]
-	      ZOrder		      -13
-	      NamePlacement	      "alternate"
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      RateTransition
-	      Name		      "Rate Transition1"
-	      SID		      "728"
-	      Position		      [735, 210, 770, 250]
-	      ZOrder		      -14
-	      OutPortSampleTime	      "0.06"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "VR Sink"
-	      SID		      "729"
-	      Ports		      [2]
-	      Position		      [865, 76, 1055, 234]
-	      ZOrder		      -15
-	      LibraryVersion	      "1.34"
-	      SourceBlock	      "vrlib/VR Sink"
-	      SourceType	      "Virtual Reality Sink"
-	      InstantiateOnLoad	      on
-	      SampleTime	      "-1"
-	      ViewEnable	      on
-	      RemoteChange	      off
-	      RemoteView	      off
-	      FieldsWritten	      "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double"
-	      WorldFileName	      "quadrotor_world_ucart.wrl"
-	      AutoView		      on
-	      VideoDimensions	      "[]"
-	      AllowVariableSize	      off
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "Bus\nCreator2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nSelector"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "Demux"
-	      SrcPort		      1
-	      Points		      [40, 0; 0, 40; 120, 0]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "Gain"
-	      SrcPort		      1
-	      Points		      [5, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "Gain2"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "Rate Transition1"
-	      SrcPort		      1
-	      Points		      [35, 0; 0, -35]
-	      DstBlock		      "VR Sink"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Rate Transition"
-	      SrcPort		      1
-	      DstBlock		      "VR Sink"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      7
-	      SrcBlock		      "Demux"
-	      SrcPort		      3
-	      DstBlock		      "Gain"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "Demux"
-	      SrcPort		      2
-	      Points		      [80, 0]
-	      DstBlock		      "Gain2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "Bus\nCreator1"
-	      SrcPort		      1
-	      DstBlock		      "Gain1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "<phi>"
-	      ZOrder		      10
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      1
-	      Points		      [0, -10; 45, 0; 0, 60]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "<psi>"
-	      ZOrder		      11
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      3
-	      Points		      [0, -10; 75, 0]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "<theta>"
-	      ZOrder		      12
-	      Labels		      [0, 0]
-	      SrcBlock		      "Bus\nSelector"
-	      SrcPort		      2
-	      Points		      [30, 0; 0, -25]
-	      DstBlock		      "Bus\nCreator"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      13
-	      SrcBlock		      "Gain1"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition1"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "psi"
-	      ZOrder		      14
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      3
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "theta"
-	      ZOrder		      15
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      2
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "phi"
-	      ZOrder		      16
-	      Labels		      [0, 0]
-	      SrcBlock		      "Demux1"
-	      SrcPort		      1
-	      DstBlock		      "Bus\nCreator2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      17
-	      SrcBlock		      "Bus\nCreator"
-	      SrcPort		      1
-	      DstBlock		      "MATLAB Function"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "MATLAB Function"
-	      SrcPort		      1
-	      DstBlock		      "Rate Transition"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "Displacement"
-	      SrcPort		      1
-	      DstBlock		      "Demux"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      20
-	      SrcBlock		      "Euler Angles\n"
-	      SrcPort		      1
-	      DstBlock		      "Demux1"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Aeb\n\n\n\n\n\n\n\n\n\n"
-	  SID			  "679"
-	  Ports			  [2, 1]
-	  Position		  [1470, 689, 1885, 811]
-	  ZOrder		  275
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    23
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU"
-	    "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode',"
-	    " 'on');"
-	  }
-	  System {
-	    Name		    "Aeb\n\n\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "25"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "gyro_reading"
-	      SID		      "679::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles_IMU"
-	      SID		      "679::22"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "679::24"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      15
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "679::23"
-	      Tag		      "Stateflow S-Function test_model_R2015A 12"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      14
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_rates_IMU"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "679::25"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      16
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_rates_IMU"
-	      SID		      "679::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "gyro_reading"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles_IMU"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "euler_rates_IMU"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_rates_IMU"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-	  SID			  "680"
-	  Ports			  [2, 2]
-	  Position		  [1480, 484, 1875, 631]
-	  ZOrder		  284
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    24
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Accelerometer Reading', 'texmode', 'on');\nport_label('output', 1, '\\theta"
-	    "_{accel}', 'texmode', 'on');\nport_label('output', 2, '\\phi_{accel}', 'texmode', 'on');\ndisp('Calculate Pitch a"
-	    "nd Roll', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "26"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_reading"
-	      SID		      "680::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_roll_prev"
-	      SID		      "680::23"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      14
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "680::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "680::19"
-	      Tag		      "Stateflow S-Function test_model_R2015A 13"
-	      Ports		      [2, 3]
-	      Position		      [180, 105, 230, 185]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 3]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"accel_pitch"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"accel_roll"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "680::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accel_pitch"
-	      SID		      "680::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accel_roll"
-	      SID		      "680::22"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "accel_reading"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "accel_roll_prev"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "accel_pitch"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "accel_pitch"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "accel_roll"
-	      ZOrder		      4
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "accel_roll"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Complimentary Filter\n\n\n\n\n\n\n\n"
-	  SID			  "657"
-	  Ports			  [3, 1]
-	  Position		  [2025, 483, 2210, 787]
-	  ZOrder		  274
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    25
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('input', 2, '\\phi_{accel}'"
-	    ", 'texmode', 'on');\nport_label('input', 3, '\\Theta_{Gyro}', 'texmode', 'on');\n%port_label('input', 4, '\\Theta"
-	    "_{IMU}', 'texmode', 'on');\nport_label('output', 1, '\\Theta_{IMU}', 'texmode', 'on');\ndisp('Complimentary Filte"
-	    "r', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Complimentary Filter\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "34"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_pitch"
-	      SID		      "657::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "accel_roll"
-	      SID		      "657::29"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      20
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles_gyro"
-	      SID		      "657::22"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      13
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "657::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "657::19"
-	      Tag		      "Stateflow S-Function test_model_R2015A 9"
-	      Ports		      [3, 2]
-	      Position		      [180, 145, 230, 225]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[3 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_angles_IMU"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "657::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_angles_IMU"
-	      SID		      "657::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      58
-	      SrcBlock		      "accel_pitch"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      59
-	      SrcBlock		      "accel_roll"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      60
-	      SrcBlock		      "euler_angles_gyro"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      Name		      "euler_angles_IMU"
-	      ZOrder		      61
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_angles_IMU"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      62
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      63
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Delay
-	  Name			  "Delay1"
-	  SID			  "731"
-	  Ports			  [1, 1]
-	  Position		  [1660, 638, 1695, 672]
-	  ZOrder		  285
-	  BlockMirror		  on
-	  ForegroundColor	  "red"
-	  InputPortMap		  "u0"
-	  DelayLength		  "1"
-	  InitialCondition	  "0"
-	  SampleTime		  "5e-3"
-	}
-	Block {
-	  BlockType		  Delay
-	  Name			  "Delay2"
-	  SID			  "772"
-	  Ports			  [1, 1]
-	  Position		  [1075, 538, 1110, 572]
-	  ZOrder		  304
-	  InputPortMap		  "u0"
-	  DelayLength		  "1"
-	  InitialCondition	  "0"
-	  SampleTime		  "5e-3"
-	}
-	Block {
-	  BlockType		  Delay
-	  Name			  "Delay3"
-	  SID			  "881"
-	  Ports			  [1, 1]
-	  Position		  [2055, 953, 2090, 987]
-	  ZOrder		  313
-	  InputPortMap		  "u0"
-	  DelayLength		  "6"
-	  SampleTime		  "0.01"
-	}
-	Block {
-	  BlockType		  Delay
-	  Name			  "Delay4"
-	  SID			  "882"
-	  Ports			  [1, 1]
-	  Position		  [2100, 998, 2135, 1032]
-	  ZOrder		  314
-	  InputPortMap		  "u0"
-	  DelayLength		  "6"
-	  SampleTime		  "0.01"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux"
-	  SID			  "732"
-	  Ports			  [1, 3]
-	  Position		  [1530, 1023, 1535, 1077]
-	  ZOrder		  294
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux1"
-	  SID			  "733"
-	  Ports			  [1, 2]
-	  Position		  [2280, 605, 2285, 660]
-	  ZOrder		  300
-	  ShowName		  off
-	  Outputs		  "2"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux2"
-	  SID			  "903"
-	  Ports			  [1, 3]
-	  Position		  [2275, 1038, 2280, 1092]
-	  ZOrder		  316
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  DiscreteIntegrator
-	  Name			  "Discrete-Time\nIntegrator"
-	  SID			  "877"
-	  Ports			  [1, 1]
-	  Position		  [1935, 732, 1970, 768]
-	  ZOrder		  309
-	  InitialConditionSetting "State (most efficient)"
-	  SampleTime		  "5e-3"
-	}
-	Block {
-	  BlockType		  Reference
-	  Name			  "First-Order\nHold"
-	  SID			  "734"
-	  Ports			  [1, 1]
-	  Position		  [2530, 780, 2565, 810]
-	  ZOrder		  292
-	  Commented		  "on"
-	  LibraryVersion	  "1.356"
-	  DisableCoverage	  on
-	  SourceBlock		  "simulink/Discrete/First-Order\nHold"
-	  SourceType		  "First-Order Hold"
-	  ContentPreviewEnabled	  off
-	  Ts			  "5e-3"
-	}
-	Block {
-	  BlockType		  Reference
-	  Name			  "First-Order\nHold1"
-	  SID			  "735"
-	  Ports			  [1, 1]
-	  Position		  [2530, 875, 2565, 905]
-	  ZOrder		  296
-	  Commented		  "on"
-	  LibraryVersion	  "1.356"
-	  DisableCoverage	  on
-	  SourceBlock		  "simulink/Discrete/First-Order\nHold"
-	  SourceType		  "First-Order Hold"
-	  ContentPreviewEnabled	  off
-	  Ts			  "5e-3"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "IMU\n\n\n\n\n\n"
-	  SID			  "658"
-	  Ports			  [4, 2]
-	  Position		  [1145, 520, 1340, 785]
-	  ZOrder		  272
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    26
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode'"
-	    ", 'on')\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')"
-	    "\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_label('output', 2, 'Gyroscope Reading',"
-	    " 'texmode', 'on')\ndisp('IMU', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "IMU\n\n\n\n\n\n"
-	    Location		    [239, 71, 1982, 1011]
-	    Open		    on
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo_dot"
-	      SID		      "659"
-	      Position		      [110, 173, 140, 187]
-	      ZOrder		      17
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo"
-	      SID		      "660"
-	      Position		      [110, 208, 140, 222]
-	      ZOrder		      25
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_Omega"
-	      SID		      "661"
-	      Position		      [110, 243, 140, 257]
-	      ZOrder		      26
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_g"
-	      SID		      "662"
-	      Position		      [110, 278, 140, 292]
-	      ZOrder		      27
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      SubSystem
-	      Name		      "\n\n\n\n\n\n\n"
-	      SID		      "663"
-	      Ports		      [5, 2]
-	      Position		      [250, 165, 445, 335]
-	      ZOrder		      1
-	      LibraryVersion	      "1.32"
-	      ErrorFcn		      "Stateflow.Translate.translate"
-	      PermitHierarchicalResolution "ExplicitOnly"
-	      TreatAsAtomicUnit	      on
-	      RequestExecContextInheritance off
-	      SFBlockType	      "MATLAB Function"
-	      Object {
-		$PropName		"MaskObject"
-		$ObjectID		27
-		$ClassName		"Simulink.Mask"
-		Display			"port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode', 'on'"
-		")\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')\nport_la"
-		"bel('input', 5, 'r_{oc}', 'texmode', 'on')\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_"
-		"label('output', 2, 'Gyroscope Reading', 'texmode', 'on')\ndisp('Ideal IMU', 'texmode', 'on');"
-	      }
-	      System {
-		Name			"\n\n\n\n\n\n\n"
-		Location		[223, 338, 826, 833]
-		Open			off
-		ModelBrowserVisibility	off
-		ModelBrowserWidth	200
-		ScreenColor		"white"
-		PaperOrientation	"landscape"
-		PaperPositionMode	"auto"
-		PaperType		"usletter"
-		PaperUnits		"inches"
-		TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-		TiledPageScale		1
-		ShowPageBoundaries	off
-		ZoomFactor		"100"
-		SIDHighWatermark	"31"
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_vo_dot"
-		  SID			  "663::1"
-		  Position		  [20, 101, 40, 119]
-		  ZOrder		  -1
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_vo"
-		  SID			  "663::22"
-		  Position		  [20, 136, 40, 154]
-		  ZOrder		  13
-		  Port			  "2"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_Omega"
-		  SID			  "663::19"
-		  Position		  [20, 171, 40, 189]
-		  ZOrder		  10
-		  Port			  "3"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "B_g"
-		  SID			  "663::20"
-		  Position		  [20, 206, 40, 224]
-		  ZOrder		  11
-		  Port			  "4"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Inport
-		  Name			  "r_oc"
-		  SID			  "663::23"
-		  Position		  [20, 246, 40, 264]
-		  ZOrder		  14
-		  Port			  "5"
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Demux
-		  Name			  " Demux "
-		  SID			  "663::25"
-		  Ports			  [1, 1]
-		  Position		  [270, 230, 320, 270]
-		  ZOrder		  16
-		  Outputs		  "1"
-		}
-		Block {
-		  BlockType		  S-Function
-		  Name			  " SFunction "
-		  SID			  "663::24"
-		  Tag			  "Stateflow S-Function test_model_R2015A 10"
-		  Ports			  [5, 3]
-		  Position		  [180, 110, 230, 230]
-		  ZOrder		  15
-		  FunctionName		  "sf_sfun"
-		  Parameters		  "g"
-		  PortCounts		  "[5 3]"
-		  EnableBusSupport	  on
-		  Port {
-		    PortNumber		    2
-		    Name		    "accelReading"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		  Port {
-		    PortNumber		    3
-		    Name		    "gyroReading"
-		    RTWStorageClass	    "Auto"
-		    DataLoggingNameMode	    "SignalName"
-		  }
-		}
-		Block {
-		  BlockType		  Terminator
-		  Name			  " Terminator "
-		  SID			  "663::26"
-		  Position		  [460, 241, 480, 259]
-		  ZOrder		  17
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "accelReading"
-		  SID			  "663::5"
-		  Position		  [460, 101, 480, 119]
-		  ZOrder		  -5
-		  IconDisplay		  "Port number"
-		}
-		Block {
-		  BlockType		  Outport
-		  Name			  "gyroReading"
-		  SID			  "663::21"
-		  Position		  [460, 136, 480, 154]
-		  ZOrder		  12
-		  Port			  "2"
-		  IconDisplay		  "Port number"
-		}
-		Line {
-		  ZOrder		  1
-		  SrcBlock		  "B_vo_dot"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  2
-		  SrcBlock		  "B_vo"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  2
-		}
-		Line {
-		  ZOrder		  3
-		  SrcBlock		  "B_Omega"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  3
-		}
-		Line {
-		  ZOrder		  4
-		  SrcBlock		  "B_g"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  4
-		}
-		Line {
-		  ZOrder		  5
-		  SrcBlock		  "r_oc"
-		  SrcPort		  1
-		  DstBlock		  " SFunction "
-		  DstPort		  5
-		}
-		Line {
-		  Name			  "accelReading"
-		  ZOrder		  6
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  2
-		  DstBlock		  "accelReading"
-		  DstPort		  1
-		}
-		Line {
-		  Name			  "gyroReading"
-		  ZOrder		  7
-		  Labels		  [0, 0]
-		  SrcBlock		  " SFunction "
-		  SrcPort		  3
-		  DstBlock		  "gyroReading"
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  8
-		  SrcBlock		  " Demux "
-		  SrcPort		  1
-		  DstBlock		  " Terminator "
-		  DstPort		  1
-		}
-		Line {
-		  ZOrder		  9
-		  SrcBlock		  " SFunction "
-		  SrcPort		  1
-		  DstBlock		  " Demux "
-		  DstPort		  1
-		}
-	      }
-	    }
-	    Block {
-	      BlockType		      Delay
-	      Name		      "Delay"
-	      SID		      "899"
-	      Ports		      [1, 1]
-	      Position		      [605, 193, 640, 227]
-	      ZOrder		      45
-	      InputPortMap	      "u0"
-	      DelayLength	      "4"
-	    }
-	    Block {
-	      BlockType		      Delay
-	      Name		      "Delay1"
-	      SID		      "900"
-	      Ports		      [1, 1]
-	      Position		      [605, 278, 640, 312]
-	      ZOrder		      46
-	      InputPortMap	      "u0"
-	      DelayLength	      "4"
-	    }
-	    Block {
-	      BlockType		      DiscreteTransferFcn
-	      Name		      "Discrete\nTransfer Fcn"
-	      SID		      "897"
-	      Ports		      [1, 1]
-	      Position		      [490, 187, 570, 233]
-	      ZOrder		      43
-	      InputPortMap	      "u0"
-	      Numerator		      "[0.02469]"
-	      Denominator	      "[1 -0.9752]"
-	      SampleTime	      "5e-3"
-	    }
-	    Block {
-	      BlockType		      DiscreteTransferFcn
-	      Name		      "Discrete\nTransfer Fcn1"
-	      SID		      "898"
-	      Ports		      [1, 1]
-	      Position		      [490, 272, 570, 318]
-	      ZOrder		      44
-	      InputPortMap	      "u0"
-	      Numerator		      "[0.02469]"
-	      Denominator	      "[1 -0.9752]"
-	      SampleTime	      "5e-3"
-	    }
-	    Block {
-	      BlockType		      DiscreteIntegrator
-	      Name		      "Discrete-Time\nIntegrator"
-	      SID		      "835"
-	      Ports		      [1, 1]
-	      Position		      [985, 372, 1020, 408]
-	      ZOrder		      30
-	      InitialConditionSetting "State (most efficient)"
-	      SampleTime	      "-1"
-	    }
-	    Block {
-	      BlockType		      DiscreteIntegrator
-	      Name		      "Discrete-Time\nIntegrator1"
-	      SID		      "837"
-	      Ports		      [1, 1]
-	      Position		      [1170, 342, 1205, 378]
-	      ZOrder		      32
-	      InitialConditionSetting "State (most efficient)"
-	      SampleTime	      "-1"
-	    }
-	    Block {
-	      BlockType		      DiscreteIntegrator
-	      Name		      "Discrete-Time\nIntegrator2"
-	      SID		      "839"
-	      Ports		      [1, 1]
-	      Position		      [1210, 247, 1245, 283]
-	      ZOrder		      34
-	      InitialConditionSetting "State (most efficient)"
-	      SampleTime	      "-1"
-	    }
-	    Block {
-	      BlockType		      DiscreteIntegrator
-	      Name		      "Discrete-Time\nIntegrator3"
-	      SID		      "841"
-	      Ports		      [1, 1]
-	      Position		      [835, 437, 870, 473]
-	      ZOrder		      36
-	      InitialConditionSetting "State (most efficient)"
-	      SampleTime	      "-1"
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground"
-	      SID		      "664"
-	      Position		      [810, 340, 830, 360]
-	      ZOrder		      23
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground1"
-	      SID		      "665"
-	      Position		      [810, 145, 830, 165]
-	      ZOrder		      24
-	    }
-	    Block {
-	      BlockType		      Integrator
-	      Name		      "Integrator"
-	      SID		      "844"
-	      Ports		      [1, 1]
-	      Position		      [240, 360, 270, 390]
-	      ZOrder		      39
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope"
-	      SID		      "836"
-	      Ports		      [1]
-	      Position		      [1065, 374, 1095, 406]
-	      ZOrder		      31
-	      Floating		      off
-	      Location		      [680, 330, 1240, 750]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.0001"
-	      YMax		      "0.00021"
-	      SaveName		      "ScopeData1"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope1"
-	      SID		      "838"
-	      Ports		      [1]
-	      Position		      [1250, 344, 1280, 376]
-	      ZOrder		      33
-	      Floating		      off
-	      Location		      [306, 114, 866, 534]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.0001"
-	      YMax		      "0.00021"
-	      SaveName		      "ScopeData2"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope2"
-	      SID		      "840"
-	      Ports		      [1]
-	      Position		      [1290, 249, 1320, 281]
-	      ZOrder		      35
-	      Floating		      off
-	      Location		      [680, 330, 1240, 750]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-1.00000"
-	      YMax		      "1.00000"
-	      SaveName		      "ScopeData3"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope3"
-	      SID		      "842"
-	      Ports		      [1]
-	      Position		      [915, 439, 945, 471]
-	      ZOrder		      37
-	      Floating		      off
-	      Location		      [306, 114, 866, 534]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-1.00000"
-	      YMax		      "1.00000"
-	      SaveName		      "ScopeData4"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope4"
-	      SID		      "843"
-	      Ports		      [1]
-	      Position		      [840, 389, 870, 421]
-	      ZOrder		      38
-	      Floating		      off
-	      Location		      [306, 114, 866, 534]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.00912"
-	      YMax		      "0.01325"
-	      SaveName		      "ScopeData5"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope5"
-	      SID		      "845"
-	      Ports		      [1]
-	      Position		      [295, 359, 325, 391]
-	      ZOrder		      40
-	      Floating		      off
-	      Location		      [306, 114, 866, 534]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-1.00000"
-	      YMax		      "1.00000"
-	      SaveName		      "ScopeData6"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum"
-	      SID		      "666"
-	      Ports		      [2, 1]
-	      Position		      [950, 285, 970, 305]
-	      ZOrder		      7
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum1"
-	      SID		      "667"
-	      Ports		      [2, 1]
-	      Position		      [950, 200, 970, 220]
-	      ZOrder		      8
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum2"
-	      SID		      "668"
-	      Ports		      [2, 1]
-	      Position		      [830, 285, 850, 305]
-	      ZOrder		      11
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum3"
-	      SID		      "669"
-	      Ports		      [2, 1]
-	      Position		      [830, 200, 850, 220]
-	      ZOrder		      12
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "accelerometer_noise"
-	      SID		      "670"
-	      Position		      [890, 140, 920, 170]
-	      ZOrder		      2
-	      Mean		      "zeros(3,1)"
-	      Variance		      "[ 3e-7 ; 3.3e-7 ; 7.2e-7 ] "
-	      Seed		      "[0,1,2]"
-	      SampleTime	      "5e-3"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "accelerometer_quantizer"
-	      SID		      "671"
-	      Position		      [1030, 195, 1060, 225]
-	      ZOrder		      9
-	      QuantizationInterval    "2.4400e-04"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "accelerometer_sampling"
-	      SID		      "672"
-	      Position		      [755, 195, 790, 225]
-	      ZOrder		      15
-	      SampleTime	      "5e-3"
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "gyroscope_noise"
-	      SID		      "673"
-	      Position		      [890, 315, 920, 345]
-	      ZOrder		      6
-	      Mean		      "zeros(3,1)"
-	      Variance		      "[ 2.2e-8 ; 1.1e-7 ; 2.4e-8 ]"
-	      Seed		      "[0,1,2]"
-	      SampleTime	      "5e-3"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "gyroscope_qunatizer"
-	      SID		      "674"
-	      Position		      [1030, 280, 1060, 310]
-	      ZOrder		      10
-	      QuantizationInterval    "1.1e-3"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "gyroscope_sampling"
-	      SID		      "675"
-	      Position		      [755, 280, 790, 310]
-	      ZOrder		      16
-	      SampleTime	      "5e-3"
-	    }
-	    Block {
-	      BlockType		      Constant
-	      Name		      "r_oc"
-	      SID		      "676"
-	      Position		      [30, 307, 95, 333]
-	      ZOrder		      28
-	      Value		      "zeros(3,1)"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "accelerometer"
-	      SID		      "677"
-	      Position		      [1100, 203, 1130, 217]
-	      ZOrder		      29
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "gyroscope"
-	      SID		      "678"
-	      Position		      [1100, 288, 1130, 302]
-	      ZOrder		      21
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "accelerometer_noise"
-	      SrcPort		      1
-	      Points		      [35, 0]
-	      DstBlock		      "Sum1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "Sum"
-	      SrcPort		      1
-	      Points		      [22, 0]
-	      Branch {
-		ZOrder			39
-		Points			[0, 65]
-		DstBlock		"Discrete-Time\nIntegrator1"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			38
-		DstBlock		"gyroscope_qunatizer"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "Sum2"
-	      SrcPort		      1
-	      DstBlock		      "Sum"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Sum3"
-	      SrcPort		      1
-	      DstBlock		      "Sum1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "gyroscope_noise"
-	      SrcPort		      1
-	      Points		      [28, 0]
-	      Branch {
-		ZOrder			35
-		Points			[0, 60]
-		DstBlock		"Discrete-Time\nIntegrator"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			34
-		Points			[7, 0]
-		DstBlock		"Sum"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      10
-	      SrcBlock		      "Sum1"
-	      SrcPort		      1
-	      DstBlock		      "accelerometer_quantizer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      11
-	      SrcBlock		      "gyroscope_sampling"
-	      SrcPort		      1
-	      Points		      [8, 0]
-	      Branch {
-		ZOrder			45
-		Points			[0, -29; -1, 0]
-		Branch {
-		  ZOrder		  52
-		  Points		  [0, -1]
-		  DstBlock		  "Discrete-Time\nIntegrator2"
-		  DstPort		  1
-		}
-		Branch {
-		  ZOrder		  51
-		  Points		  [-81, 0; 0, 189; 72, 0]
-		  Branch {
-		    ZOrder		    47
-		    Points		    [0, -50]
-		    DstBlock		    "Scope4"
-		    DstPort		    1
-		  }
-		  Branch {
-		    ZOrder		    46
-		    DstBlock		    "Discrete-Time\nIntegrator3"
-		    DstPort		    1
-		  }
-		}
-	      }
-	      Branch {
-		ZOrder			44
-		DstBlock		"Sum2"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      12
-	      SrcBlock		      "accelerometer_sampling"
-	      SrcPort		      1
-	      DstBlock		      "Sum3"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      13
-	      SrcBlock		      "Ground"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum2"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      14
-	      SrcBlock		      "Ground1"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      15
-	      SrcBlock		      "B_vo_dot"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      16
-	      SrcBlock		      "B_vo"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      17
-	      SrcBlock		      "B_Omega"
-	      SrcPort		      1
-	      Points		      [48, 0]
-	      Branch {
-		ZOrder			50
-		Points			[0, 125]
-		DstBlock		"Integrator"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			49
-		DstBlock		"\n\n\n\n\n\n\n"
-		DstPort			3
-	      }
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "B_g"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      4
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "r_oc"
-	      SrcPort		      1
-	      DstBlock		      "\n\n\n\n\n\n\n"
-	      DstPort		      5
-	    }
-	    Line {
-	      ZOrder		      36
-	      SrcBlock		      "Discrete-Time\nIntegrator"
-	      SrcPort		      1
-	      DstBlock		      "Scope"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      37
-	      SrcBlock		      "Discrete-Time\nIntegrator1"
-	      SrcPort		      1
-	      DstBlock		      "Scope1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      40
-	      SrcBlock		      "Discrete-Time\nIntegrator2"
-	      SrcPort		      1
-	      DstBlock		      "Scope2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      43
-	      SrcBlock		      "Discrete-Time\nIntegrator3"
-	      SrcPort		      1
-	      DstBlock		      "Scope3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      48
-	      SrcBlock		      "Integrator"
-	      SrcPort		      1
-	      DstBlock		      "Scope5"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      64
-	      SrcBlock		      "gyroscope_qunatizer"
-	      SrcPort		      1
-	      DstBlock		      "gyroscope"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      65
-	      SrcBlock		      "accelerometer_quantizer"
-	      SrcPort		      1
-	      DstBlock		      "accelerometer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      79
-	      SrcBlock		      "\n\n\n\n\n\n\n"
-	      SrcPort		      1
-	      DstBlock		      "Discrete\nTransfer Fcn"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      80
-	      SrcBlock		      "\n\n\n\n\n\n\n"
-	      SrcPort		      2
-	      DstBlock		      "Discrete\nTransfer Fcn1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      81
-	      SrcBlock		      "Discrete\nTransfer Fcn"
-	      SrcPort		      1
-	      DstBlock		      "Delay"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      82
-	      SrcBlock		      "Discrete\nTransfer Fcn1"
-	      SrcPort		      1
-	      DstBlock		      "Delay1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      83
-	      SrcBlock		      "Delay"
-	      SrcPort		      1
-	      DstBlock		      "accelerometer_sampling"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      84
-	      SrcBlock		      "Delay1"
-	      SrcPort		      1
-	      DstBlock		      "gyroscope_sampling"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Mux
-	  Name			  "Mux"
-	  SID			  "736"
-	  Ports			  [3, 1]
-	  Position		  [2455, 608, 2460, 682]
-	  ZOrder		  301
-	  ShowName		  off
-	  Inputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "OptiTrack Camera System\n\n       "
-	  SID			  "681"
-	  Ports			  [2, 2]
-	  Position		  [1720, 906, 1950, 1039]
-	  ZOrder		  299
-	  ShowName		  off
-	  RequestExecContextInheritance	off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    28
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^{E}r_o', 'texmode', 'on');\nport_label('input', 2, '\\psi', 'texmode', 'on"
-	    "');\nport_label('output', 1, '^{E}r_o camera', 'texmode', 'on');\nport_label('output', 2, '\\psi camera', 'texmod"
-	    "e', 'on');\ndisp('OptiTrack Camera System', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "OptiTrack Camera System\n\n       "
-	    Location		    [69, 48, 1812, 988]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "150"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "E_ro"
-	      SID		      "682"
-	      Position		      [295, 238, 325, 252]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw"
-	      SID		      "683"
-	      Position		      [295, 338, 325, 352]
-	      ZOrder		      4
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "E_ro_noise"
-	      SID		      "684"
-	      Position		      [545, 175, 575, 205]
-	      ZOrder		      30
-	      Mean		      "zeros(3,1)"
-	      Variance		      "[ 7.9664e-10 ; 1.1928e-10 ; 5.0636e-10 ] "
-	      Seed		      "[0,1,2]"
-	      SampleTime	      "0.01"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "E_ro_quantizer"
-	      SID		      "685"
-	      Position		      [685, 230, 715, 260]
-	      ZOrder		      34
-	      QuantizationInterval    "2.4400e-04"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "E_ro_sampling"
-	      SID		      "686"
-	      Position		      [410, 230, 445, 260]
-	      ZOrder		      38
-	      SampleTime	      "0.01"
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground1"
-	      SID		      "687"
-	      Position		      [465, 180, 485, 200]
-	      ZOrder		      42
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      "Ground2"
-	      SID		      "688"
-	      Position		      [465, 390, 485, 410]
-	      ZOrder		      56
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum1"
-	      SID		      "689"
-	      Ports		      [2, 1]
-	      Position		      [605, 235, 625, 255]
-	      ZOrder		      33
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum3"
-	      SID		      "690"
-	      Ports		      [2, 1]
-	      Position		      [485, 235, 505, 255]
-	      ZOrder		      37
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "++|"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum4"
-	      SID		      "691"
-	      Ports		      [2, 1]
-	      Position		      [605, 335, 625, 355]
-	      ZOrder		      47
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum6"
-	      SID		      "692"
-	      Ports		      [2, 1]
-	      Position		      [485, 335, 505, 355]
-	      ZOrder		      51
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|++"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      RandomNumber
-	      Name		      "yaw_noise"
-	      SID		      "693"
-	      Position		      [545, 365, 575, 395]
-	      ZOrder		      46
-	      Mean		      "zeros(3,1)"
-	      Variance		      "1.0783e-9*ones(3,1)"
-	      SampleTime	      "0.01"
-	    }
-	    Block {
-	      BlockType		      Quantizer
-	      Name		      "yaw_quantizer"
-	      SID		      "694"
-	      Position		      [685, 330, 715, 360]
-	      ZOrder		      50
-	      QuantizationInterval    "1.1e-3"
-	    }
-	    Block {
-	      BlockType		      ZeroOrderHold
-	      Name		      "yaw_sampling"
-	      SID		      "695"
-	      Position		      [410, 330, 445, 360]
-	      ZOrder		      54
-	      SampleTime	      "0.01"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "E_ro_camera"
-	      SID		      "696"
-	      Position		      [800, 238, 830, 252]
-	      ZOrder		      43
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "yaw_camera"
-	      SID		      "697"
-	      Position		      [800, 338, 830, 352]
-	      ZOrder		      55
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "E_ro_noise"
-	      SrcPort		      1
-	      Points		      [35, 0]
-	      DstBlock		      "Sum1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "Sum3"
-	      SrcPort		      1
-	      DstBlock		      "Sum1"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "Sum1"
-	      SrcPort		      1
-	      DstBlock		      "E_ro_quantizer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "E_ro_sampling"
-	      SrcPort		      1
-	      DstBlock		      "Sum3"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      "Ground1"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      "Sum4"
-	      SrcPort		      1
-	      DstBlock		      "yaw_quantizer"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      "Sum6"
-	      SrcPort		      1
-	      DstBlock		      "Sum4"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      10
-	      SrcBlock		      "yaw_noise"
-	      SrcPort		      1
-	      Points		      [35, 0]
-	      DstBlock		      "Sum4"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      11
-	      SrcBlock		      "yaw_sampling"
-	      SrcPort		      1
-	      DstBlock		      "Sum6"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      12
-	      SrcBlock		      "Ground2"
-	      SrcPort		      1
-	      Points		      [5, 0]
-	      DstBlock		      "Sum6"
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      17
-	      SrcBlock		      "yaw"
-	      SrcPort		      1
-	      DstBlock		      "yaw_sampling"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      18
-	      SrcBlock		      "E_ro"
-	      SrcPort		      1
-	      DstBlock		      "E_ro_sampling"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      19
-	      SrcBlock		      "E_ro_quantizer"
-	      SrcPort		      1
-	      DstBlock		      "E_ro_camera"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      20
-	      SrcBlock		      "yaw_quantizer"
-	      SrcPort		      1
-	      DstBlock		      "yaw_camera"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope"
-	  SID			  "737"
-	  Ports			  [1]
-	  Position		  [1385, 669, 1415, 701]
-	  ZOrder		  270
-	  Floating		  off
-	  Location		  [680, 330, 1240, 750]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-0.00277"
-	  YMax			  "0.00209"
-	  SaveName		  "ScopeData1"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope1"
-	  SID			  "738"
-	  Ports			  [1]
-	  Position		  [1385, 599, 1415, 631]
-	  ZOrder		  271
-	  Floating		  off
-	  Location		  [10, 76, 1918, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-2.04337"
-	  YMax			  "0.22704"
-	  SaveName		  "ScopeData2"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope2"
-	  SID			  "849"
-	  Ports			  [1]
-	  Position		  [2550, 534, 2580, 566]
-	  ZOrder		  308
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-182.40701"
-	  YMax			  "117.99145"
-	  SaveName		  "ScopeData7"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope3"
-	  SID			  "739"
-	  Ports			  [1]
-	  Position		  [2255, 534, 2285, 566]
-	  ZOrder		  278
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-0.05134"
-	  YMax			  "0.44242"
-	  SaveName		  "ScopeData4"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope6"
-	  SID			  "740"
-	  Ports			  [1]
-	  Position		  [1955, 469, 1985, 501]
-	  ZOrder		  280
-	  Floating		  off
-	  Location		  [1, 76, 1909, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-1.00000"
-	  YMax			  "1.00000"
-	  SaveName		  "ScopeData5"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope7"
-	  SID			  "741"
-	  Ports			  [1]
-	  Position		  [1955, 544, 1985, 576]
-	  ZOrder		  281
-	  Floating		  off
-	  Location		  [1, 76, 1909, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-1.00000"
-	  YMax			  "1.00000"
-	  SaveName		  "ScopeData6"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  S-Function
-	  Name			  "Soft Real Time"
-	  SID			  "742"
-	  Ports			  []
-	  Position		  [2618, 735, 2705, 766]
-	  ZOrder		  288
-	  ShowName		  off
-	  Commented		  "on"
-	  FunctionName		  "sfun_time"
-	  Parameters		  "x"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    29
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "color('red')\ndisp('Soft Real Time')\n"
-	    Object {
-	      $PropName		      "Parameters"
-	      $ObjectID		      30
-	      $ClassName	      "Simulink.MaskParameter"
-	      Type		      "edit"
-	      Name		      "x"
-	      Prompt		      "Time Scaling Factor"
-	      Value		      "1"
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "euler_angles_filtered"
-	  SID			  "743"
-	  Position		  [2535, 638, 2565, 652]
-	  ZOrder		  262
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "euler_rates"
-	  SID			  "744"
-	  Position		  [1395, 798, 1430, 812]
-	  ZOrder		  259
-	  ForegroundColor	  "red"
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "current_position"
-	  SID			  "745"
-	  Position		  [2335, 963, 2365, 977]
-	  ZOrder		  289
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "camera_euler"
-	  SID			  "904"
-	  Position		  [2430, 1038, 2460, 1052]
-	  ZOrder		  317
-	  Port			  "4"
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "IMU\n\n\n\n\n\n"
-	  SrcPort		  1
-	  Points		  [23, 0]
-	  Branch {
-	    ZOrder		    2
-	    Points		    [0, -70]
-	    DstBlock		    "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    3
-	    Points		    [0, 25]
-	    DstBlock		    "Scope1"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  4
-	  SrcBlock		  "IMU\n\n\n\n\n\n"
-	  SrcPort		  2
-	  Points		  [15, 0]
-	  Branch {
-	    ZOrder		    5
-	    Points		    [0, -35]
-	    DstBlock		    "Scope"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    6
-	    Points		    [19, 0]
-	    Branch {
-	      ZOrder		      160
-	      Points		      [0, 85]
-	      DstBlock		      "euler_rates"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      159
-	      DstBlock		      "Aeb\n\n\n\n\n\n\n\n\n\n"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  8
-	  SrcBlock		  "B_vo"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  9
-	  SrcBlock		  "B_Omega"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  10
-	  SrcBlock		  "B_g"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  4
-	}
-	Line {
-	  ZOrder		  11
-	  SrcBlock		  "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-	  SrcPort		  2
-	  Points		  [17, 0]
-	  Branch {
-	    ZOrder		    12
-	    Points		    [0, 60]
-	    DstBlock		    "Delay1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    13
-	    Points		    [31, 0]
-	    Branch {
-	      ZOrder		      14
-	      Points		      [82, 0]
-	      DstBlock		      "Complimentary Filter\n\n\n\n\n\n\n\n"
-	      DstPort		      2
-	    }
-	    Branch {
-	      ZOrder		      15
-	      Points		      [0, -35]
-	      DstBlock		      "Scope7"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  16
-	  SrcBlock		  "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-	  SrcPort		  1
-	  Points		  [47, 0]
-	  Branch {
-	    ZOrder		    17
-	    Points		    [83, 0]
-	    DstBlock		    "Complimentary Filter\n\n\n\n\n\n\n\n"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    18
-	    Points		    [0, -35]
-	    DstBlock		    "Scope6"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  25
-	  SrcBlock		  "Delay1"
-	  SrcPort		  1
-	  Points		  [-199, 0; 0, -60]
-	  DstBlock		  "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  26
-	  SrcBlock		  "euler_angles"
-	  SrcPort		  1
-	  Points		  [23, 0]
-	  Branch {
-	    ZOrder		    210
-	    Points		    [0, -45]
-	    DstBlock		    "OptiTrack Camera System\n\n       "
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    27
-	    Points		    [0, 70]
-	    DstBlock		    "3D Graphical Simulation"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    28
-	    DstBlock		    "Demux"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  29
-	  SrcBlock		  "Complimentary Filter\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  Points		  [16, 0]
-	  Branch {
-	    ZOrder		    77
-	    Points		    [0, 222; -789, 0; 0, -77]
-	    DstBlock		    "Aeb\n\n\n\n\n\n\n\n\n\n"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    30
-	    DstBlock		    "Demux1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    69
-	    Points		    [0, -85]
-	    DstBlock		    "Scope3"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  33
-	  SrcBlock		  "First-Order\nHold"
-	  SrcPort		  1
-	  Points		  [50, 0]
-	  DstBlock		  "3D Graphical Simulation1"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  34
-	  SrcBlock		  "E_ro"
-	  SrcPort		  1
-	  Points		  [196, 0]
-	  Branch {
-	    ZOrder		    35
-	    Points		    [0, 120]
-	    DstBlock		    "3D Graphical Simulation"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    36
-	    Points		    [0, -30]
-	    DstBlock		    "OptiTrack Camera System\n\n       "
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  38
-	  SrcBlock		  "First-Order\nHold1"
-	  SrcPort		  1
-	  Points		  [30, 0; 0, -30]
-	  DstBlock		  "3D Graphical Simulation1"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  39
-	  SrcBlock		  "Demux1"
-	  SrcPort		  1
-	  DstBlock		  "Mux"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  40
-	  SrcBlock		  "Demux1"
-	  SrcPort		  2
-	  DstBlock		  "Mux"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  41
-	  SrcBlock		  "OptiTrack Camera System\n\n       "
-	  SrcPort		  2
-	  Points		  [70, 0; 0, 10]
-	  DstBlock		  "Delay4"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  42
-	  SrcBlock		  "Mux"
-	  SrcPort		  1
-	  Points		  [31, 0]
-	  Branch {
-	    ZOrder		    117
-	    Points		    [0, -95]
-	    DstBlock		    "Scope2"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    98
-	    Points		    [0, 150]
-	    DstBlock		    "First-Order\nHold"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    97
-	    DstBlock		    "euler_angles_filtered"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  45
-	  SrcBlock		  "OptiTrack Camera System\n\n       "
-	  SrcPort		  1
-	  Points		  [48, 0; 0, 30]
-	  DstBlock		  "Delay3"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  62
-	  SrcBlock		  "B_vo_dot"
-	  SrcPort		  1
-	  DstBlock		  "Delay2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  63
-	  SrcBlock		  "Delay2"
-	  SrcPort		  1
-	  DstBlock		  "IMU\n\n\n\n\n\n"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  202
-	  SrcBlock		  "Aeb\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  DstBlock		  "Discrete-Time\nIntegrator"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  201
-	  SrcBlock		  "Discrete-Time\nIntegrator"
-	  SrcPort		  1
-	  Points		  [20, 0; 0, -15]
-	  DstBlock		  "Complimentary Filter\n\n\n\n\n\n\n\n"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  203
-	  SrcBlock		  "Delay3"
-	  SrcPort		  1
-	  Points		  [183, 0]
-	  Branch {
-	    ZOrder		    100
-	    Points		    [0, -80]
-	    DstBlock		    "First-Order\nHold1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    99
-	    DstBlock		    "current_position"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  211
-	  SrcBlock		  "Delay4"
-	  SrcPort		  1
-	  Points		  [81, 0; 0, 16]
-	  Branch {
-	    ZOrder		    214
-	    Points		    [144, 0; 0, 14]
-	    DstBlock		    "camera_euler"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    213
-	    Points		    [0, 34]
-	    DstBlock		    "Demux2"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  212
-	  SrcBlock		  "Demux2"
-	  SrcPort		  3
-	  Points		  [14, 0; 0, -415]
-	  DstBlock		  "Mux"
-	  DstPort		  3
-	}
-      }
-    }
-    Block {
-      BlockType		      SubSystem
-      Name		      "Actuation"
-      SID		      "436"
-      Ports		      [1, 6]
-      Position		      [850, 276, 1100, 504]
-      ZOrder		      71
-      ShowName		      off
-      RequestExecContextInheritance off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		31
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('input', 1, 'Rotor Duty Cycles', 'texmode', 'on');\nport_label('output', 1, '^{B}Omega', 'texmo"
-	"de', 'on');\nport_label('output', 2, '\\Theta', 'texmode', 'on');\nport_label('output', 3, '^{B}v_o', 'texmode', 'on'"
-	");\nport_label('output', 4, '^{E}r_o', 'texmode', 'on');\nport_label('output', 5, '^{B}dv_o/dt', 'texmode', 'on');\np"
-	"ort_label('output', 6, '^{B}g', 'texmode', 'on');\ndisp('Actuation', 'texmode', 'on'); "
-      }
-      System {
-	Name			"Actuation"
-	Location		[108, 36, 1850, 976]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"80"
-	Block {
-	  BlockType		  Inport
-	  Name			  "Rotor Duty Cycles"
-	  SID			  "437"
-	  Position		  [20, 393, 50, 407]
-	  ZOrder		  -1
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SID			  "446"
-	  Ports			  [2, 1]
-	  Position		  [1435, 303, 1670, 452]
-	  ZOrder		  81
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    32
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^B\\Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode',"
-	    " 'on');\nport_label('output', 1, 'd\\Theta/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "25"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_omega"
-	      SID		      "446::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles"
-	      SID		      "446::22"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      13
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "446::24"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      15
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "446::23"
-	      Tag		      "Stateflow S-Function test_model_R2015A 7"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      14
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"euler_rates"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "446::25"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      16
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "euler_rates"
-	      SID		      "446::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "B_omega"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "euler_rates"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "euler_rates"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux1"
-	  SID			  "449"
-	  Ports			  [1, 3]
-	  Position		  [1870, 526, 1875, 574]
-	  ZOrder		  107
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "x position"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "y position"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "z position"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux2"
-	  SID			  "450"
-	  Ports			  [1, 3]
-	  Position		  [1870, 301, 1875, 349]
-	  ZOrder		  109
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Roll"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Pitch"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Yaw"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux3"
-	  SID			  "451"
-	  Ports			  [1, 3]
-	  Position		  [1870, 406, 1875, 454]
-	  ZOrder		  117
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Body x velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Body y velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Body z velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux4"
-	  SID			  "452"
-	  Ports			  [1, 3]
-	  Position		  [1870, 161, 1875, 209]
-	  ZOrder		  115
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Body roll velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Body pitch velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Body yaw velocity"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux5"
-	  SID			  "453"
-	  Ports			  [1, 3]
-	  Position		  [1870, 641, 1875, 689]
-	  ZOrder		  119
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	  Port {
-	    PortNumber		    1
-	    Name		    "Body x acceleration"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    2
-	    Name		    "Body y acceleration"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	  Port {
-	    PortNumber		    3
-	    Name		    "Body z acceleration"
-	    RTWStorageClass	    "Auto"
-	    DataLoggingNameMode	    "SignalName"
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "ESC System"
-	  SID			  "442"
-	  Ports			  [1, 1]
-	  Position		  [95, 282, 330, 518]
-	  ZOrder		  36
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    33
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Rotor Duty Cycle', 'texmode', 'on');\nport_label('output', 1, 'Vb_{eff}', '"
-	    "texmode', 'on');\ndisp('ESC System');"
-	  }
-	  System {
-	    Name		    "ESC System"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "37"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "rotor_duty_cycles"
-	      SID		      "442::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "442::36"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      17
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "442::35"
-	      Tag		      "Stateflow S-Function test_model_R2015A 4"
-	      Ports		      [1, 2]
-	      Position		      [180, 105, 230, 165]
-	      ZOrder		      16
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "Pmax,Pmin,Vb"
-	      PortCounts	      "[1 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"Vb_eff"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "442::37"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      18
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "Vb_eff"
-	      SID		      "442::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      34
-	      SrcBlock		      "rotor_duty_cycles"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "Vb_eff"
-	      ZOrder		      35
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "Vb_eff"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      36
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      37
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Gravity\n\n"
-	  SID			  "443"
-	  Ports			  [0, 1]
-	  Position		  [375, 664, 525, 786]
-	  ZOrder		  96
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    34
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('output', 1, '^EF_g', 'texmode', 'on');\nfprintf('Gravity');\n"
-	  }
-	  System {
-	    Name		    "Gravity\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "30"
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "443::28"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      19
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      Ground
-	      Name		      " Ground "
-	      SID		      "443::30"
-	      Position		      [20, 121, 40, 139]
-	      ZOrder		      21
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "443::27"
-	      Tag		      "Stateflow S-Function test_model_R2015A 1"
-	      Ports		      [1, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      18
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "g,m"
-	      PortCounts	      "[1 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"E_Fg"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "443::29"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      20
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "E_Fg"
-	      SID		      "443::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      Name		      "E_Fg"
-	      ZOrder		      1
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "E_Fg"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      " Ground "
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator"
-	  SID			  "454"
-	  Ports			  [1, 1]
-	  Position		  [770, 340, 800, 370]
-	  ZOrder		  49
-	  InitialCondition	  "[omega_o, omega_o, omega_o, omega_o]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator1"
-	  SID			  "455"
-	  Ports			  [1, 1]
-	  Position		  [1265, 445, 1295, 475]
-	  ZOrder		  53
-	  InitialCondition	  "[0; 0; 0]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator2"
-	  SID			  "456"
-	  Ports			  [1, 1]
-	  Position		  [1265, 325, 1295, 355]
-	  ZOrder		  54
-	  InitialCondition	  "[0; 0; 0]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator3"
-	  SID			  "457"
-	  Ports			  [1, 1]
-	  Position		  [1725, 590, 1755, 620]
-	  ZOrder		  98
-	  InitialCondition	  "[0; 0; 0]"
-	}
-	Block {
-	  BlockType		  Integrator
-	  Name			  "Integrator4"
-	  SID			  "458"
-	  Ports			  [1, 1]
-	  Position		  [1725, 365, 1755, 395]
-	  ZOrder		  77
-	  InitialCondition	  "[0; 0; 0]"
-	  ContinuousStateAttributes "['phi' 'theta' 'psi']"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Lbe\n\n\n\n\n\n"
-	  SID			  "444"
-	  Ports			  [2, 1]
-	  Position		  [1435, 499, 1670, 706]
-	  ZOrder		  75
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    35
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^Bv_o', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on"
-	    "');\nport_label('output', 1, '^Ev_o', 'texmode', 'on');\ndisp('L_{EB}', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Lbe\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "31"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo"
-	      SID		      "444::24"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      15
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles"
-	      SID		      "444::28"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      19
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "444::30"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      21
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "444::29"
-	      Tag		      "Stateflow S-Function test_model_R2015A 2"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      20
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[2 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"E_ro"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "444::31"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      22
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "E_ro"
-	      SID		      "444::26"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      17
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "B_vo"
-	      SrcPort		      1
-	      Points		      [120, 0]
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "E_ro"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "E_ro"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SID			  "447"
-	  Ports			  [2, 2]
-	  Position		  [640, 694, 810, 816]
-	  ZOrder		  97
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    36
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^EF_g', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on"
-	    "');\nport_label('output', 1, '^BF_g', 'texmode', 'on');\ndisp('L_{BE}', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "33"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "E_Fg"
-	      SID		      "447::24"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      15
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "euler_angles"
-	      SID		      "447::28"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      19
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "447::30"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      21
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "447::29"
-	      Tag		      "Stateflow S-Function test_model_R2015A 8"
-	      Ports		      [2, 3]
-	      Position		      [180, 100, 230, 180]
-	      ZOrder		      20
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "m"
-	      PortCounts	      "[2 3]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"B_Fg"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"B_g"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "447::31"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      22
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_Fg"
-	      SID		      "447::26"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      17
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_g"
-	      SID		      "447::32"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      23
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "E_Fg"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "euler_angles"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "B_Fg"
-	      ZOrder		      3
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "B_Fg"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "B_g"
-	      ZOrder		      4
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "B_g"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      6
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Motor System"
-	  SID			  "441"
-	  Ports			  [2, 1]
-	  Position		  [460, 280, 680, 520]
-	  ZOrder		  48
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    37
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, 'Vb_{eff}', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', "
-	    "'on');\nport_label('output', 1, '\\alpha', 'texmode', 'on');\ndisp('Motor System');\n"
-	  }
-	  System {
-	    Name		    "Motor System"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "35"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "Vb_eff"
-	      SID		      "441::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "angular_velocity"
-	      SID		      "441::35"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      20
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "441::32"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      17
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "441::31"
-	      Tag		      "Stateflow S-Function test_model_R2015A 5"
-	      Ports		      [2, 2]
-	      Position		      [180, 100, 230, 160]
-	      ZOrder		      16
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "If,Jreq,Kd,Kq,Kv,Rm"
-	      PortCounts	      "[2 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"angular_acceleration"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "441::33"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      18
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "angular_acceleration"
-	      SID		      "441::23"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      14
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      33
-	      SrcBlock		      "Vb_eff"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      34
-	      SrcBlock		      "angular_velocity"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      Name		      "angular_acceleration"
-	      ZOrder		      35
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "angular_acceleration"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      36
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      37
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Rotor System\n\n\n\n\n\n\n\n"
-	  SID			  "758"
-	  Ports			  [5, 2]
-	  Position		  [985, 281, 1185, 519]
-	  ZOrder		  122
-	  ShowName		  off
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    38
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '\\alpha', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', '"
-	    "on');\nport_label('input', 3, '^BF_g', 'texmode', 'on');\nport_label('input', 4, '^B\\Omega', 'texmode', 'on');\n"
-	    "port_label('input', 5, '^Bv_o', 'texmode', 'on');\nport_label('output', 1, '^Bd\\Omega/dt', 'texmode', 'on');\npo"
-	    "rt_label('output', 2, '^Bdv_o/dt', 'texmode', 'on');\ndisp('Rotor System', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Rotor System\n\n\n\n\n\n\n\n"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "50"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "angular_acceleration"
-	      SID		      "758::27"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      18
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "angular_velocity"
-	      SID		      "758::28"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      19
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_Fg"
-	      SID		      "758::47"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      20
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_omega"
-	      SID		      "758::25"
-	      Position		      [20, 206, 40, 224]
-	      ZOrder		      16
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "B_vo"
-	      SID		      "758::24"
-	      Position		      [20, 246, 40, 264]
-	      ZOrder		      15
-	      Port		      "5"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "758::49"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      22
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "758::48"
-	      Tag		      "Stateflow S-Function test_model_R2015A 6"
-	      Ports		      [5, 3]
-	      Position		      [180, 100, 230, 220]
-	      ZOrder		      21
-	      FunctionName	      "sf_sfun"
-	      Parameters	      "Jreq,Jxx,Jyy,Jzz,Kd,Kt,m,rhx,rhy,rhz"
-	      PortCounts	      "[5 3]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"B_omega_dot"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	      Port {
-		PortNumber		3
-		Name			"B_vo_dot"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "758::50"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      23
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_omega_dot"
-	      SID		      "758::22"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      13
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "B_vo_dot"
-	      SID		      "758::5"
-	      Position		      [460, 136, 480, 154]
-	      ZOrder		      -5
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      1
-	      SrcBlock		      "angular_acceleration"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      2
-	      SrcBlock		      "angular_velocity"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      3
-	      SrcBlock		      "B_Fg"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      4
-	      SrcBlock		      "B_omega"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      4
-	    }
-	    Line {
-	      ZOrder		      5
-	      SrcBlock		      "B_vo"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      5
-	    }
-	    Line {
-	      Name		      "B_omega_dot"
-	      ZOrder		      6
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "B_omega_dot"
-	      DstPort		      1
-	    }
-	    Line {
-	      Name		      "B_vo_dot"
-	      ZOrder		      7
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      3
-	      DstBlock		      "B_vo_dot"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      8
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      9
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      Points		      [20, 0]
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope"
-	  SID			  "459"
-	  Ports			  [1]
-	  Position		  [390, 279, 420, 311]
-	  ZOrder		  46
-	  Floating		  off
-	  Location		  [188, 365, 512, 604]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-1.3875"
-	  YMax			  "12.4875"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope1"
-	  SID			  "460"
-	  Ports			  [1]
-	  Position		  [780, 229, 810, 261]
-	  ZOrder		  50
-	  Floating		  off
-	  Location		  [1, 76, 1909, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  ShowLegends		  on
-	  YMin			  "-10513.81558"
-	  YMax			  "11401.07279"
-	  SaveName		  "ScopeData1"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope10"
-	  SID			  "461"
-	  Ports			  [3]
-	  Position		  [1975, 303, 2015, 347]
-	  ZOrder		  108
-	  Floating		  off
-	  Location		  [1, 76, 1909, 1039]
-	  Open			  off
-	  NumInputPorts		  "3"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  ShowLegends		  on
-	  YMin			  "-60.66007~-1.00000~-1.00000"
-	  YMax			  "18.5091~1.00000~1.00000"
-	  SaveName		  "ScopeData1"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope11"
-	  SID			  "462"
-	  Ports			  [3]
-	  Position		  [1975, 163, 2015, 207]
-	  ZOrder		  114
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "3"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  ShowLegends		  on
-	  YMin			  "-3.00603~-1.00000~-1.00000"
-	  YMax			  "4.56766~1.00000~1.00000"
-	  SaveName		  "ScopeData3"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope2"
-	  SID			  "463"
-	  Ports			  [1]
-	  Position		  [930, 229, 960, 261]
-	  ZOrder		  51
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-88.20659"
-	  YMax			  "679.8109"
-	  SaveName		  "ScopeData2"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope3"
-	  SID			  "464"
-	  Ports			  [3]
-	  Position		  [1975, 408, 2015, 452]
-	  ZOrder		  116
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "3"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  ShowLegends		  on
-	  YMin			  "-1.00000~-71.40595~-81.80792"
-	  YMax			  "1.00000~93.1255~67.47699"
-	  SaveName		  "ScopeData2"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope4"
-	  SID			  "465"
-	  Ports			  [3]
-	  Position		  [1975, 643, 2015, 687]
-	  ZOrder		  118
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "3"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  ShowLegends		  on
-	  YMin			  "-1019.9483~-1019.9483~-1019.9483"
-	  YMax			  "1049.2638~1049.2638~1049.2638"
-	  SaveName		  "ScopeData4"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope6"
-	  SID			  "466"
-	  Ports			  [3]
-	  Position		  [1975, 528, 2015, 572]
-	  ZOrder		  79
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "3"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	    axes2		    "%<SignalLabel>"
-	    axes3		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  ShowLegends		  on
-	  YMin			  "-1.00000~-1.00000~-0.09265"
-	  YMax			  "1.00000~1.00000~0.0667"
-	  SaveName		  "ScopeData4"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope7"
-	  SID			  "467"
-	  Ports			  [1]
-	  Position		  [575, 644, 605, 676]
-	  ZOrder		  99
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-1.45924"
-	  YMax			  "13.13314"
-	  SaveName		  "ScopeData1"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope8"
-	  SID			  "468"
-	  Ports			  [1]
-	  Position		  [860, 629, 890, 661]
-	  ZOrder		  100
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-14.59237"
-	  YMax			  "14.59237"
-	  SaveName		  "ScopeData2"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope9"
-	  SID			  "469"
-	  Ports			  [1]
-	  Position		  [1265, 229, 1295, 261]
-	  ZOrder		  102
-	  Floating		  off
-	  Location		  [1, 76, 1921, 1039]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "-9.72639"
-	  YMax			  "9.72632"
-	  SaveName		  "ScopeData3"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_omega"
-	  SID			  "471"
-	  Position		  [1855, 238, 1885, 252]
-	  ZOrder		  61
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "euler_angles"
-	  SID			  "472"
-	  Position		  [1910, 373, 1940, 387]
-	  ZOrder		  91
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_vo"
-	  SID			  "473"
-	  Position		  [1855, 468, 1885, 482]
-	  ZOrder		  58
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "E_ro"
-	  SID			  "474"
-	  Position		  [1870, 598, 1900, 612]
-	  ZOrder		  88
-	  Port			  "4"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_vo_dot"
-	  SID			  "475"
-	  Position		  [1870, 718, 1900, 732]
-	  ZOrder		  103
-	  Port			  "5"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "B_g"
-	  SID			  "476"
-	  Position		  [1870, 778, 1900, 792]
-	  ZOrder		  104
-	  Port			  "6"
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "ESC System"
-	  SrcPort		  1
-	  Points		  [23, 0; 0, -59]
-	  Branch {
-	    ZOrder		    2
-	    Points		    [2, 0; 0, -46]
-	    DstBlock		    "Scope"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    3
-	    Points		    [0, -1]
-	    DstBlock		    "Motor System"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  4
-	  SrcBlock		  "Motor System"
-	  SrcPort		  1
-	  Points		  [40, 0; 0, -45]
-	  Branch {
-	    ZOrder		    5
-	    DstBlock		    "Integrator"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    6
-	    Points		    [0, -45]
-	    Branch {
-	      ZOrder		      101
-	      DstBlock		      "Rotor System\n\n\n\n\n\n\n\n"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      7
-	      Points		      [0, -65]
-	      DstBlock		      "Scope1"
-	      DstPort		      1
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  9
-	  SrcBlock		  "Integrator"
-	  SrcPort		  1
-	  Points		  [68, 0]
-	  Branch {
-	    ZOrder		    290
-	    Points		    [0, 210; -473, 0; 0, -105]
-	    DstBlock		    "Motor System"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    292
-	    DstBlock		    "Rotor System\n\n\n\n\n\n\n\n"
-	    DstPort		    2
-	  }
-	  Branch {
-	    ZOrder		    291
-	    Points		    [0, -110]
-	    DstBlock		    "Scope2"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  103
-	  SrcBlock		  "Rotor System\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  Points		  [39, 0]
-	  Branch {
-	    ZOrder		    15
-	    Points		    [0, -95]
-	    DstBlock		    "Scope9"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    16
-	    DstBlock		    "Integrator2"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  22
-	  SrcBlock		  "Integrator2"
-	  SrcPort		  1
-	  Points		  [55, 0]
-	  Branch {
-	    ZOrder		    105
-	    Points		    [0, 252; -416, 0; 0, -147]
-	    DstBlock		    "Rotor System\n\n\n\n\n\n\n\n"
-	    DstPort		    4
-	  }
-	  Branch {
-	    ZOrder		    23
-	    Points		    [0, -95; 454, 0]
-	    Branch {
-	      ZOrder		      24
-	      DstBlock		      "B_omega"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      25
-	      Points		      [0, -60]
-	      DstBlock		      "Demux4"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    27
-	    DstBlock		    "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  28
-	  SrcBlock		  "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  DstBlock		  "Integrator4"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  29
-	  SrcBlock		  "Gravity\n\n"
-	  SrcPort		  1
-	  Points		  [7, 0]
-	  Branch {
-	    ZOrder		    30
-	    Points		    [0, -65]
-	    DstBlock		    "Scope7"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    31
-	    DstBlock		    "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  32
-	  SrcBlock		  "Lbe\n\n\n\n\n\n"
-	  SrcPort		  1
-	  DstBlock		  "Integrator3"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  33
-	  SrcBlock		  "Integrator3"
-	  SrcPort		  1
-	  Points		  [64, 0]
-	  Branch {
-	    ZOrder		    34
-	    Points		    [0, -55]
-	    DstBlock		    "Demux1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    35
-	    DstBlock		    "E_ro"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  36
-	  SrcBlock		  "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  1
-	  Points		  [24, 0; 0, -1]
-	  Branch {
-	    ZOrder		    107
-	    Points		    [82, 0; 0, -324]
-	    DstBlock		    "Rotor System\n\n\n\n\n\n\n\n"
-	    DstPort		    3
-	  }
-	  Branch {
-	    ZOrder		    106
-	    Points		    [0, -79]
-	    DstBlock		    "Scope8"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  39
-	  SrcBlock		  "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	  SrcPort		  2
-	  DstBlock		  "B_g"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "y position"
-	  ZOrder		  45
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux1"
-	  SrcPort		  2
-	  DstBlock		  "Scope6"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "x position"
-	  ZOrder		  46
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux1"
-	  SrcPort		  1
-	  DstBlock		  "Scope6"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "z position"
-	  ZOrder		  47
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux1"
-	  SrcPort		  3
-	  DstBlock		  "Scope6"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Pitch"
-	  ZOrder		  57
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux2"
-	  SrcPort		  2
-	  DstBlock		  "Scope10"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Roll"
-	  ZOrder		  58
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux2"
-	  SrcPort		  1
-	  DstBlock		  "Scope10"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Yaw"
-	  ZOrder		  59
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux2"
-	  SrcPort		  3
-	  DstBlock		  "Scope10"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Body pitch velocity"
-	  ZOrder		  60
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux4"
-	  SrcPort		  2
-	  DstBlock		  "Scope11"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Body roll velocity"
-	  ZOrder		  61
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux4"
-	  SrcPort		  1
-	  DstBlock		  "Scope11"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Body yaw velocity"
-	  ZOrder		  62
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux4"
-	  SrcPort		  3
-	  DstBlock		  "Scope11"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Body y velocity"
-	  ZOrder		  63
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux3"
-	  SrcPort		  2
-	  DstBlock		  "Scope3"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Body x velocity"
-	  ZOrder		  64
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux3"
-	  SrcPort		  1
-	  DstBlock		  "Scope3"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Body z velocity"
-	  ZOrder		  65
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux3"
-	  SrcPort		  3
-	  DstBlock		  "Scope3"
-	  DstPort		  3
-	}
-	Line {
-	  Name			  "Body y acceleration"
-	  ZOrder		  66
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux5"
-	  SrcPort		  2
-	  DstBlock		  "Scope4"
-	  DstPort		  2
-	}
-	Line {
-	  Name			  "Body x acceleration"
-	  ZOrder		  67
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux5"
-	  SrcPort		  1
-	  DstBlock		  "Scope4"
-	  DstPort		  1
-	}
-	Line {
-	  Name			  "Body z acceleration"
-	  ZOrder		  68
-	  Labels		  [0, 0]
-	  SrcBlock		  "Demux5"
-	  SrcPort		  3
-	  DstBlock		  "Scope4"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  69
-	  SrcBlock		  "Integrator1"
-	  SrcPort		  1
-	  Points		  [34, 0; 0, 90]
-	  Branch {
-	    ZOrder		    104
-	    Points		    [-370, 0; 0, -60]
-	    DstBlock		    "Rotor System\n\n\n\n\n\n\n\n"
-	    DstPort		    5
-	  }
-	  Branch {
-	    ZOrder		    71
-	    Points		    [76, 0]
-	    Branch {
-	      ZOrder		      72
-	      DstBlock		      "Lbe\n\n\n\n\n\n"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      73
-	      Points		      [0, -75; 401, 0]
-	      Branch {
-		ZOrder			74
-		Points			[0, -45]
-		DstBlock		"Demux3"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			75
-		DstBlock		"B_vo"
-		DstPort			1
-	      }
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  102
-	  SrcBlock		  "Rotor System\n\n\n\n\n\n\n\n"
-	  SrcPort		  2
-	  Points		  [27, 0]
-	  Branch {
-	    ZOrder		    205
-	    Points		    [0, 265; 607, 0]
-	    Branch {
-	      ZOrder		      201
-	      Points		      [0, -60]
-	      DstBlock		      "Demux5"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      200
-	      DstBlock		      "B_vo_dot"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    198
-	    DstBlock		    "Integrator1"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  48
-	  SrcBlock		  "Integrator4"
-	  SrcPort		  1
-	  Points		  [20, 0]
-	  Branch {
-	    ZOrder		    277
-	    Points		    [60, 0]
-	    Branch {
-	      ZOrder		      50
-	      Points		      [0, -55]
-	      DstBlock		      "Demux2"
-	      DstPort		      1
-	    }
-	    Branch {
-	      ZOrder		      51
-	      DstBlock		      "euler_angles"
-	      DstPort		      1
-	    }
-	  }
-	  Branch {
-	    ZOrder		    52
-	    Points		    [0, 502; -385, 0]
-	    Branch {
-	      ZOrder		      352
-	      Points		      [0, -227]
-	      Branch {
-		ZOrder			54
-		DstBlock		"Lbe\n\n\n\n\n\n"
-		DstPort			2
-	      }
-	      Branch {
-		ZOrder			55
-		Points			[0, -240]
-		DstBlock		"Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-		DstPort			2
-	      }
-	    }
-	    Branch {
-	      ZOrder		      56
-	      Points		      [-787, 0; 0, -97]
-	      DstBlock		      "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-	      DstPort		      2
-	    }
-	  }
-	}
-	Line {
-	  ZOrder		  286
-	  SrcBlock		  "Rotor Duty Cycles"
-	  SrcPort		  1
-	  DstBlock		  "ESC System"
-	  DstPort		  1
-	}
-      }
-    }
-    Block {
-      BlockType		      SubSystem
-      Name		      "Communication System"
-      SID		      "582"
-      Ports		      [0, 1]
-      Position		      [405, 282, 460, 328]
-      ZOrder		      70
-      RequestExecContextInheritance off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		39
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('output', 1, 'Setpoints', 'texmode', 'on');"
-      }
-      System {
-	Name			"Communication System"
-	Location		[126, 17, 1868, 957]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"300"
-	Block {
-	  BlockType		  Step
-	  Name			  "Step"
-	  SID			  "583"
-	  Position		  [925, 390, 955, 420]
-	  ZOrder		  32
-	  Before		  "[0; 0; 0; 0]"
-	  After			  "[1; 0; 0; 0]"
-	  SampleTime		  "0.1"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "setpoints"
-	  SID			  "584"
-	  Position		  [1050, 398, 1080, 412]
-	  ZOrder		  6
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "Step"
-	  SrcPort		  1
-	  DstBlock		  "setpoints"
-	  DstPort		  1
-	}
-      }
-    }
-    Block {
-      BlockType		      SubSystem
-      Name		      "Control System"
-      SID		      "573"
-      Ports		      [4, 1]
-      Position		      [540, 275, 795, 500]
-      ZOrder		      69
-      ShowName		      off
-      RequestExecContextInheritance off
-      Object {
-	$PropName		"MaskObject"
-	$ObjectID		40
-	$ClassName		"Simulink.Mask"
-	Display			"port_label('input', 1, 'Setpoints', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{filtered}', 'texmo"
-	"de', 'on');\nport_label('input', 3, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmo"
-	"de', 'on');\nport_label('output', 1, 'Motor Commands', 'texmode', 'on');\ndisp('Control System', 'texmode', 'on');"
-      }
-      System {
-	Name			"Control System"
-	Location		[69, 48, 1812, 988]
-	Open			off
-	ModelBrowserVisibility	off
-	ModelBrowserWidth	200
-	ScreenColor		"white"
-	PaperOrientation	"landscape"
-	PaperPositionMode	"auto"
-	PaperType		"usletter"
-	PaperUnits		"inches"
-	TiledPaperMargins	[0.500000, 0.500000, 0.500000, 0.500000]
-	TiledPageScale		1
-	ShowPageBoundaries	off
-	ZoomFactor		"125"
-	Block {
-	  BlockType		  Inport
-	  Name			  "setpoints"
-	  SID			  "574"
-	  Position		  [230, 353, 260, 367]
-	  ZOrder		  2
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "euler_angles_filtered"
-	  SID			  "575"
-	  Position		  [230, 513, 260, 527]
-	  ZOrder		  9
-	  Port			  "2"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "euler_rates"
-	  SID			  "576"
-	  Position		  [215, 588, 245, 602]
-	  ZOrder		  11
-	  Port			  "3"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  Inport
-	  Name			  "current_position"
-	  SID			  "577"
-	  Position		  [215, 438, 245, 452]
-	  ZOrder		  -1
-	  Port			  "4"
-	  IconDisplay		  "Port number"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "Controller"
-	  SID			  "604"
-	  Ports			  [13, 4]
-	  Position		  [395, 307, 530, 633]
-	  ZOrder		  31
-	  RequestExecContextInheritance	off
-	  Object {
-	    $PropName		    "MaskObject"
-	    $ObjectID		    41
-	    $ClassName		    "Simulink.Mask"
-	    Display		    "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se"
-	    "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', "
-	    "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'"
-	    ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\"
-	    "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't"
-	    "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '"
-	    "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode"
-	    "', 'on');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\npo"
-	    "rt_label('output', 4, 'u_R', 'texmode', 'on');\ndisp('Controller', 'texmode', 'on');"
-	  }
-	  System {
-	    Name		    "Controller"
-	    Location		    [69, 48, 1812, 988]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "125"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "x_setpoint"
-	      SID		      "605"
-	      Position		      [135, 403, 165, 417]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "y_setpoint"
-	      SID		      "607"
-	      Position		      [135, 248, 165, 262]
-	      ZOrder		      45
-	      ForegroundColor	      "gray"
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "z_setpoint"
-	      SID		      "608"
-	      Position		      [130, 128, 160, 142]
-	      ZOrder		      46
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw_setpoint"
-	      SID		      "632"
-	      Position		      [130, 553, 160, 567]
-	      ZOrder		      103
-	      ForegroundColor	      "gray"
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "x_position"
-	      SID		      "622"
-	      Position		      [165, 468, 195, 482]
-	      ZOrder		      60
-	      Port		      "5"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "y_position"
-	      SID		      "623"
-	      Position		      [165, 313, 195, 327]
-	      ZOrder		      61
-	      Port		      "6"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "z_position"
-	      SID		      "624"
-	      Position		      [160, 183, 190, 197]
-	      ZOrder		      62
-	      Port		      "7"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "roll"
-	      SID		      "630"
-	      Position		      [300, 313, 330, 327]
-	      ZOrder		      68
-	      Port		      "8"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "pitch"
-	      SID		      "631"
-	      Position		      [300, 468, 330, 482]
-	      ZOrder		      69
-	      Port		      "9"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw"
-	      SID		      "649"
-	      Position		      [160, 608, 190, 622]
-	      ZOrder		      105
-	      Port		      "10"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "roll_rate"
-	      SID		      "633"
-	      Position		      [525, 313, 555, 327]
-	      ZOrder		      71
-	      Port		      "11"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "pitch_rate"
-	      SID		      "634"
-	      Position		      [525, 468, 555, 482]
-	      ZOrder		      72
-	      Port		      "12"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw_rate"
-	      SID		      "635"
-	      Position		      [300, 608, 330, 622]
-	      ZOrder		      73
-	      Port		      "13"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain1"
-	      SID		      "891"
-	      Position		      [810, 117, 860, 153]
-	      ZOrder		      151
-	      Gain		      "5e4"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain2"
-	      SID		      "892"
-	      Position		      [810, 237, 860, 273]
-	      ZOrder		      152
-	      Gain		      "5e4"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain3"
-	      SID		      "893"
-	      Position		      [810, 392, 860, 428]
-	      ZOrder		      153
-	      Gain		      "5e4"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Gain
-	      Name		      "Gain4"
-	      SID		      "894"
-	      Position		      [810, 542, 860, 578]
-	      ZOrder		      154
-	      Gain		      "5e4"
-	      ParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller1"
-	      SID		      "873"
-	      Ports		      [1, 1]
-	      Position		      [645, 392, 685, 428]
-	      ZOrder		      142
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "P"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "5e-3"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "0.015166894231541"
-	      I			      "1575.82088970639"
-	      D			      "504.111397357926"
-	      N			      "244.660686071579"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller10"
-	      SID		      "833"
-	      Ports		      [1, 1]
-	      Position		      [260, 542, 300, 578]
-	      ZOrder		      122
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "0.01"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "1.69332227925298"
-	      I			      "0.373031053213692"
-	      D			      "0.0846661139626488"
-	      N			      "17.8214030142826"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller11"
-	      SID		      "834"
-	      Ports		      [1, 1]
-	      Position		      [260, 117, 300, 153]
-	      ZOrder		      123
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PID"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "0.01"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "-0.0153859651723572"
-	      I			      "-0.000331343308727455"
-	      D			      "-0.178612271980841"
-	      N			      "5.79502261645411"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller2"
-	      SID		      "832"
-	      Ports		      [1, 1]
-	      Position		      [645, 541, 685, 579]
-	      ZOrder		      121
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PI"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "5e-3"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "0.137082785475467"
-	      I			      "1.78239822850373"
-	      D			      "2.32"
-	      N			      "1/0.0818"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      off
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller3"
-	      SID		      "874"
-	      Ports		      [1, 1]
-	      Position		      [505, 392, 545, 428]
-	      ZOrder		      143
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "P"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "5e-3"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "1.37514874127105"
-	      I			      "35.1207902652377"
-	      D			      "0.410623594074865"
-	      N			      "40.0107970227961"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller4"
-	      SID		      "876"
-	      Ports		      [1, 1]
-	      Position		      [260, 392, 300, 428]
-	      ZOrder		      145
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "0.01"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "-0.00209477698719004"
-	      I			      "-5.49963745752816e-05"
-	      D			      "-0.116816668948546"
-	      N			      "16.9491526069154"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller6"
-	      SID		      "867"
-	      Ports		      [1, 1]
-	      Position		      [260, 237, 300, 273]
-	      ZOrder		      136
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "PD"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "0.01"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      off
-	      ControllerParametersSource "internal"
-	      P			      "0.00209477698719004"
-	      I			      "9.56340991394167e-06"
-	      D			      "0.116816668948546"
-	      N			      "16.9491526069154"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller8"
-	      SID		      "868"
-	      Ports		      [1, 1]
-	      Position		      [505, 237, 545, 273]
-	      ZOrder		      137
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "P"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "5e-3"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "1.37514874127105"
-	      I			      "35.1207902652377"
-	      D			      "0.2"
-	      N			      "40.0107970227961"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Reference
-	      Name		      "PID Controller9"
-	      SID		      "869"
-	      Ports		      [1, 1]
-	      Position		      [645, 237, 685, 273]
-	      ZOrder		      138
-	      LibraryVersion	      "1.356"
-	      SourceBlock	      "simulink/Continuous/PID Controller"
-	      SourceType	      "PID 1dof"
-	      ContentPreviewEnabled   off
-	      Controller	      "P"
-	      TimeDomain	      "Discrete-time"
-	      SampleTime	      "5e-3"
-	      IntegratorMethod	      "Forward Euler"
-	      FilterMethod	      "Forward Euler"
-	      Form		      "Parallel"
-	      UseFilter		      on
-	      ControllerParametersSource "internal"
-	      P			      "0.015166894231541"
-	      I			      "1575.82088970639"
-	      D			      "504.111397357926"
-	      N			      "244.660686071579"
-	      InitialConditionSource  "internal"
-	      InitialConditionForIntegrator "0"
-	      InitialConditionForFilter	"0"
-	      ExternalReset	      "none"
-	      IgnoreLimit	      off
-	      ZeroCross		      on
-	      LimitOutput	      off
-	      UpperSaturationLimit    "inf"
-	      LowerSaturationLimit    "-inf"
-	      LinearizeAsGain	      on
-	      AntiWindupMode	      "none"
-	      Kb		      "1"
-	      TrackingMode	      off
-	      Kt		      "1"
-	      RndMeth		      "Floor"
-	      SaturateOnIntegerOverflow	off
-	      LockScale		      off
-	      PParamMin		      "[]"
-	      PParamMax		      "[]"
-	      PParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IParamMin		      "[]"
-	      IParamMax		      "[]"
-	      IParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DParamMin		      "[]"
-	      DParamMax		      "[]"
-	      DParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NParamMin		      "[]"
-	      NParamMax		      "[]"
-	      NParamDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KbParamMin	      "[]"
-	      KbParamMax	      "[]"
-	      KbParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      KtParamMin	      "[]"
-	      KtParamMax	      "[]"
-	      KtParamDataTypeStr      "Inherit: Inherit via internal rule"
-	      POutMin		      "[]"
-	      POutMax		      "[]"
-	      POutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      PGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      PProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IOutMin		      "[]"
-	      IOutMax		      "[]"
-	      IOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      IProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DOutMin		      "[]"
-	      DOutMax		      "[]"
-	      DOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      DGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      DProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NOutMin		      "[]"
-	      NOutMax		      "[]"
-	      NOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      NGainOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      NProdOutDataTypeStr     "Inherit: Inherit via internal rule"
-	      KbOutMin		      "[]"
-	      KbOutMax		      "[]"
-	      KbOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      KtOutMin		      "[]"
-	      KtOutMax		      "[]"
-	      KtOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      IntegratorOutMin	      "[]"
-	      IntegratorOutMax	      "[]"
-	      IntegratorOutDataTypeStr "Inherit: Inherit via internal rule"
-	      FilterOutMin	      "[]"
-	      FilterOutMax	      "[]"
-	      FilterOutDataTypeStr    "Inherit: Inherit via internal rule"
-	      SumOutMin		      "[]"
-	      SumOutMax		      "[]"
-	      SumOutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SumI1OutMin	      "[]"
-	      SumI1OutMax	      "[]"
-	      SumI1OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI2OutMin	      "[]"
-	      SumI2OutMax	      "[]"
-	      SumI2OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI3OutMin	      "[]"
-	      SumI3OutMax	      "[]"
-	      SumI3OutDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumDOutMin	      "[]"
-	      SumDOutMax	      "[]"
-	      SumDOutDataTypeStr      "Inherit: Inherit via internal rule"
-	      SumAccumDataTypeStr     "Inherit: Inherit via internal rule"
-	      SumI1AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI2AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumI3AccumDataTypeStr   "Inherit: Inherit via internal rule"
-	      SumDAccumDataTypeStr    "Inherit: Inherit via internal rule"
-	      SaturationOutMin	      "[]"
-	      SaturationOutMax	      "[]"
-	      SaturationOutDataTypeStr "Inherit: Same as input"
-	      IntegratorContinuousStateAttributes "''"
-	      IntegratorStateMustResolveToSignalObject off
-	      IntegratorRTWStateStorageClass "Auto"
-	      FilterContinuousStateAttributes "''"
-	      FilterStateMustResolveToSignalObject off
-	      FilterRTWStateStorageClass "Auto"
-	      DifferentiatorICPrevScaledInput "0"
-	      DifferentiatorOutMin    "[]"
-	      DifferentiatorOutMax    "[]"
-	      DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule"
-	    }
-	    Block {
-	      BlockType		      Saturate
-	      Name		      "Saturation1"
-	      SID		      "887"
-	      Ports		      [1, 1]
-	      Position		      [410, 240, 440, 270]
-	      ZOrder		      147
-	      Commented		      "through"
-	      InputPortMap	      "u0"
-	      UpperLimit	      "20*pi/180"
-	      LowerLimit	      "-20*pi/180"
-	    }
-	    Block {
-	      BlockType		      Saturate
-	      Name		      "Saturation2"
-	      SID		      "888"
-	      Ports		      [1, 1]
-	      Position		      [410, 395, 440, 425]
-	      ZOrder		      148
-	      Commented		      "through"
-	      InputPortMap	      "u0"
-	      UpperLimit	      "20*pi/180"
-	      LowerLimit	      "-20*pi/180"
-	    }
-	    Block {
-	      BlockType		      Saturate
-	      Name		      "Saturation3"
-	      SID		      "889"
-	      Ports		      [1, 1]
-	      Position		      [410, 545, 440, 575]
-	      ZOrder		      149
-	      Commented		      "through"
-	      InputPortMap	      "u0"
-	      UpperLimit	      "20*pi/180"
-	      LowerLimit	      "-20*pi/180"
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope"
-	      SID		      "791"
-	      Ports		      [1]
-	      Position		      [510, 649, 540, 681]
-	      ZOrder		      97
-	      Floating		      off
-	      Location		      [1, 76, 1921, 1039]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-4.53199"
-	      YMax		      "5.80666"
-	      SaveName		      "ScopeData1"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope1"
-	      SID		      "792"
-	      Ports		      [1]
-	      Position		      [235, 649, 265, 681]
-	      ZOrder		      106
-	      Floating		      off
-	      Location		      [10, 76, 1926, 1039]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.00426"
-	      YMax		      "0.00536"
-	      SaveName		      "ScopeData2"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope2"
-	      SID		      "795"
-	      Ports		      [1]
-	      Position		      [265, 174, 295, 206]
-	      ZOrder		      107
-	      Floating		      off
-	      Location		      [593, 266, 1926, 1046]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.5 0.5 0.5]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[1 1 1]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.14356"
-	      YMax		      "1.29207"
-	      SaveName		      "ScopeData5"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope3"
-	      SID		      "797"
-	      Ports		      [1]
-	      Position		      [650, 334, 680, 366]
-	      ZOrder		      109
-	      Floating		      off
-	      Location		      [10, 76, 1926, 1039]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.13447"
-	      YMax		      "1.21019"
-	      SaveName		      "ScopeData1"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope4"
-	      SID		      "798"
-	      Ports		      [1]
-	      Position		      [365, 334, 395, 366]
-	      ZOrder		      110
-	      Floating		      off
-	      Location		      [10, 76, 1926, 1039]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.2"
-	      YMax		      "0.5"
-	      SaveName		      "ScopeData2"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope5"
-	      SID		      "799"
-	      Ports		      [1]
-	      Position		      [240, 334, 270, 366]
-	      ZOrder		      111
-	      Floating		      off
-	      Location		      [1, 49, 1921, 1039]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.5 0.5 0.5]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[1 1 1]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.035"
-	      YMax		      "0.03"
-	      SaveName		      "ScopeData3"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope6"
-	      SID		      "825"
-	      Ports		      [1]
-	      Position		      [650, 484, 680, 516]
-	      ZOrder		      117
-	      Floating		      off
-	      Location		      [10, 76, 1926, 1039]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.48276"
-	      YMax		      "2.87086"
-	      SaveName		      "ScopeData1"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope7"
-	      SID		      "826"
-	      Ports		      [1]
-	      Position		      [365, 484, 395, 516]
-	      ZOrder		      118
-	      Floating		      off
-	      Location		      [10, 76, 1926, 1039]
-	      Open		      off
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.156862745098039 0.156862745098039 0.156862745098039]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[0.686274509803922 0.686274509803922 0.686274509803922]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      YMin		      "-0.04704"
-	      YMax		      "0.39309"
-	      SaveName		      "ScopeData2"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Scope
-	      Name		      "Scope8"
-	      SID		      "827"
-	      Ports		      [1]
-	      Position		      [245, 484, 275, 516]
-	      ZOrder		      119
-	      Floating		      off
-	      Location		      [2, 57, 1918, 1038]
-	      Open		      on
-	      NumInputPorts	      "1"
-	      List {
-		ListType		AxesTitles
-		axes1			"%<SignalLabel>"
-	      }
-	      List {
-		ListType		ScopeGraphics
-		FigureColor		"[0.5 0.5 0.5]"
-		AxesColor		"[0 0 0]"
-		AxesTickColor		"[1 1 1]"
-		LineColors		"[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-		LineStyles		"-|-|-|-|-|-"
-		LineWidths		"[0.5 0.5 0.5 0.5 0.5 0.5]"
-		MarkerStyles		"none|none|none|none|none|none"
-	      }
-	      TimeRange		      "20"
-	      YMin		      "2200"
-	      YMax		      "4300"
-	      SaveName		      "ScopeData3"
-	      DataFormat	      "StructureWithTime"
-	      LimitDataPoints	      off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum"
-	      SID		      "598"
-	      Ports		      [2, 1]
-	      Position		      [350, 550, 370, 570]
-	      ZOrder		      40
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum1"
-	      SID		      "599"
-	      Ports		      [2, 1]
-	      Position		      [340, 245, 360, 265]
-	      ZOrder		      41
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum2"
-	      SID		      "600"
-	      Ports		      [2, 1]
-	      Position		      [590, 245, 610, 265]
-	      ZOrder		      42
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum3"
-	      SID		      "602"
-	      Ports		      [2, 1]
-	      Position		      [335, 400, 355, 420]
-	      ZOrder		      43
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum4"
-	      SID		      "603"
-	      Ports		      [2, 1]
-	      Position		      [590, 400, 610, 420]
-	      ZOrder		      44
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum5"
-	      SID		      "618"
-	      Ports		      [2, 1]
-	      Position		      [215, 400, 235, 420]
-	      ZOrder		      56
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum6"
-	      SID		      "619"
-	      Ports		      [2, 1]
-	      Position		      [210, 245, 230, 265]
-	      ZOrder		      57
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum7"
-	      SID		      "620"
-	      Ports		      [2, 1]
-	      Position		      [210, 125, 230, 145]
-	      ZOrder		      58
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Sum
-	      Name		      "Sum8"
-	      SID		      "648"
-	      Ports		      [2, 1]
-	      Position		      [210, 550, 230, 570]
-	      ZOrder		      104
-	      ShowName		      off
-	      IconShape		      "round"
-	      Inputs		      "|+-"
-	      InputSameDT	      off
-	      OutDataTypeStr	      "Inherit: Inherit via internal rule"
-	      SaturateOnIntegerOverflow	off
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "height_controlled"
-	      SID		      "606"
-	      Position		      [925, 128, 955, 142]
-	      ZOrder		      -2
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "y_controlled"
-	      SID		      "636"
-	      Position		      [925, 248, 955, 262]
-	      ZOrder		      74
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "x_controlled"
-	      SID		      "637"
-	      Position		      [925, 403, 955, 417]
-	      ZOrder		      75
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "yaw_controlled"
-	      SID		      "638"
-	      Position		      [925, 553, 955, 567]
-	      ZOrder		      76
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      283
-	      SrcBlock		      "Sum"
-	      SrcPort		      1
-	      DstBlock		      "Saturation3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      43
-	      SrcBlock		      "pitch"
-	      SrcPort		      1
-	      Points		      [9, 0]
-	      Branch {
-		ZOrder			233
-		Points			[0, 25]
-		DstBlock		"Scope7"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			232
-		Points			[1, 0]
-		DstBlock		"Sum3"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      42
-	      SrcBlock		      "roll"
-	      SrcPort		      1
-	      Points		      [15, 0]
-	      Branch {
-		ZOrder			218
-		DstBlock		"Scope4"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			215
-		DstBlock		"Sum1"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      48
-	      SrcBlock		      "pitch_rate"
-	      SrcPort		      1
-	      Points		      [40, 0]
-	      Branch {
-		ZOrder			229
-		DstBlock		"Sum4"
-		DstPort			2
-	      }
-	      Branch {
-		ZOrder			228
-		Points			[0, 25]
-		DstBlock		"Scope6"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      47
-	      SrcBlock		      "roll_rate"
-	      SrcPort		      1
-	      Points		      [40, 0]
-	      Branch {
-		ZOrder			123
-		Points			[0, 30]
-		DstBlock		"Scope3"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			122
-		DstBlock		"Sum2"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      49
-	      SrcBlock		      "yaw_rate"
-	      SrcPort		      1
-	      Points		      [25, 0]
-	      Branch {
-		ZOrder			173
-		Points			[0, 50]
-		DstBlock		"Scope"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			87
-		DstBlock		"Sum"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      26
-	      SrcBlock		      "z_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum7"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      28
-	      SrcBlock		      "y_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum6"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      31
-	      SrcBlock		      "x_position"
-	      SrcPort		      1
-	      Points		      [25, 0]
-	      Branch {
-		ZOrder			237
-		DstBlock		"Sum5"
-		DstPort			2
-	      }
-	      Branch {
-		ZOrder			236
-		Points			[0, 25]
-		DstBlock		"Scope8"
-		DstPort			1
-	      }
-	    }
-	    Line {
-	      ZOrder		      32
-	      SrcBlock		      "x_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum5"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      33
-	      SrcBlock		      "y_position"
-	      SrcPort		      1
-	      Points		      [20, 0]
-	      Branch {
-		ZOrder			241
-		Points			[0, 30]
-		DstBlock		"Scope5"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			128
-		DstBlock		"Sum6"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      34
-	      SrcBlock		      "z_position"
-	      SrcPort		      1
-	      Points		      [25, 0]
-	      Branch {
-		ZOrder			108
-		DstBlock		"Scope2"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			107
-		DstBlock		"Sum7"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      100
-	      SrcBlock		      "yaw"
-	      SrcPort		      1
-	      Points		      [25, 0]
-	      Branch {
-		ZOrder			172
-		DstBlock		"Scope1"
-		DstPort			1
-	      }
-	      Branch {
-		ZOrder			102
-		DstBlock		"Sum8"
-		DstPort			2
-	      }
-	    }
-	    Line {
-	      ZOrder		      98
-	      SrcBlock		      "yaw_setpoint"
-	      SrcPort		      1
-	      DstBlock		      "Sum8"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      434
-	      SrcBlock		      "Sum2"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller9"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      416
-	      SrcBlock		      "Sum6"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller6"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      461
-	      SrcBlock		      "Sum5"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller4"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      281
-	      SrcBlock		      "Sum7"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller11"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      285
-	      SrcBlock		      "Sum8"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller10"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      451
-	      SrcBlock		      "Sum4"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      456
-	      SrcBlock		      "PID Controller1"
-	      SrcPort		      1
-	      DstBlock		      "Gain3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      459
-	      SrcBlock		      "Sum3"
-	      SrcPort		      1
-	      DstBlock		      "Saturation2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      462
-	      SrcBlock		      "PID Controller4"
-	      SrcPort		      1
-	      DstBlock		      "Sum3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      464
-	      SrcBlock		      "PID Controller9"
-	      SrcPort		      1
-	      DstBlock		      "Gain2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      473
-	      SrcBlock		      "PID Controller11"
-	      SrcPort		      1
-	      DstBlock		      "Gain1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      478
-	      SrcBlock		      "PID Controller2"
-	      SrcPort		      1
-	      DstBlock		      "Gain4"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      482
-	      SrcBlock		      "Sum1"
-	      SrcPort		      1
-	      DstBlock		      "Saturation1"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      486
-	      SrcBlock		      "Saturation2"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller3"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      488
-	      SrcBlock		      "Gain1"
-	      SrcPort		      1
-	      DstBlock		      "height_controlled"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      489
-	      SrcBlock		      "Gain2"
-	      SrcPort		      1
-	      DstBlock		      "y_controlled"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      490
-	      SrcBlock		      "Gain3"
-	      SrcPort		      1
-	      DstBlock		      "x_controlled"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      491
-	      SrcBlock		      "Gain4"
-	      SrcPort		      1
-	      DstBlock		      "yaw_controlled"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      492
-	      SrcBlock		      "PID Controller3"
-	      SrcPort		      1
-	      DstBlock		      "Sum4"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      493
-	      SrcBlock		      "Saturation3"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      496
-	      SrcBlock		      "Saturation1"
-	      SrcPort		      1
-	      DstBlock		      "PID Controller8"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      498
-	      SrcBlock		      "PID Controller10"
-	      SrcPort		      1
-	      DstBlock		      "Sum"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      500
-	      SrcBlock		      "PID Controller8"
-	      SrcPort		      1
-	      DstBlock		      "Sum2"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      501
-	      SrcBlock		      "PID Controller6"
-	      SrcPort		      1
-	      DstBlock		      "Sum1"
-	      DstPort		      1
-	    }
-	    Annotation {
-	      SID		      "901"
-	      Name		      "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">"
-	      "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap"
-	      "; }\n</style></head><body style=\" font-family:'Helvetica'; font-size:10px; font-weight:400; font-style:normal;"
-	      "\">\n<p style=\"-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px;"
-	      " -qt-block-indent:0; text-indent:0px;\"><br /></p></body></html>"
-	      Position		      [264, 366, 266, 381]
-	      InternalMargins	      [0, 0, 0, 0]
-	      FixedHeight	      off
-	      FixedWidth	      off
-	      HorizontalAlignment     "left"
-	      VerticalAlignment	      "top"
-	      Interpreter	      "rich"
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux"
-	  SID			  "586"
-	  Ports			  [1, 4]
-	  Position		  [300, 309, 305, 406]
-	  ZOrder		  13
-	  ShowName		  off
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux1"
-	  SID			  "639"
-	  Ports			  [1, 3]
-	  Position		  [300, 484, 305, 556]
-	  ZOrder		  32
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux2"
-	  SID			  "588"
-	  Ports			  [1, 3]
-	  Position		  [285, 409, 290, 481]
-	  ZOrder		  15
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  Demux
-	  Name			  "Demux4"
-	  SID			  "640"
-	  Ports			  [1, 3]
-	  Position		  [275, 559, 280, 631]
-	  ZOrder		  33
-	  ShowName		  off
-	  Outputs		  "3"
-	  DisplayOption		  "bar"
-	}
-	Block {
-	  BlockType		  SubSystem
-	  Name			  "MATLAB Function"
-	  SID			  "647"
-	  Ports			  [4, 1]
-	  Position		  [725, 308, 925, 632]
-	  ZOrder		  35
-	  ErrorFcn		  "Stateflow.Translate.translate"
-	  PermitHierarchicalResolution "ExplicitOnly"
-	  TreatAsAtomicUnit	  on
-	  RequestExecContextInheritance	off
-	  SFBlockType		  "MATLAB Function"
-	  System {
-	    Name		    "MATLAB Function"
-	    Location		    [223, 338, 826, 833]
-	    Open		    off
-	    ModelBrowserVisibility  off
-	    ModelBrowserWidth	    200
-	    ScreenColor		    "white"
-	    PaperOrientation	    "landscape"
-	    PaperPositionMode	    "auto"
-	    PaperType		    "usletter"
-	    PaperUnits		    "inches"
-	    TiledPaperMargins	    [0.500000, 0.500000, 0.500000, 0.500000]
-	    TiledPageScale	    1
-	    ShowPageBoundaries	    off
-	    ZoomFactor		    "100"
-	    SIDHighWatermark	    "27"
-	    Block {
-	      BlockType		      Inport
-	      Name		      "height_controlled"
-	      SID		      "647::1"
-	      Position		      [20, 101, 40, 119]
-	      ZOrder		      -1
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "y_controlled"
-	      SID		      "647::23"
-	      Position		      [20, 136, 40, 154]
-	      ZOrder		      14
-	      Port		      "2"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "x_controlled"
-	      SID		      "647::22"
-	      Position		      [20, 171, 40, 189]
-	      ZOrder		      13
-	      Port		      "3"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Inport
-	      Name		      "yaw_controlled"
-	      SID		      "647::24"
-	      Position		      [20, 206, 40, 224]
-	      ZOrder		      15
-	      Port		      "4"
-	      IconDisplay	      "Port number"
-	    }
-	    Block {
-	      BlockType		      Demux
-	      Name		      " Demux "
-	      SID		      "647::20"
-	      Ports		      [1, 1]
-	      Position		      [270, 230, 320, 270]
-	      ZOrder		      11
-	      Outputs		      "1"
-	    }
-	    Block {
-	      BlockType		      S-Function
-	      Name		      " SFunction "
-	      SID		      "647::19"
-	      Tag		      "Stateflow S-Function test_model_R2015A 14"
-	      Ports		      [4, 2]
-	      Position		      [180, 107, 230, 208]
-	      ZOrder		      10
-	      FunctionName	      "sf_sfun"
-	      PortCounts	      "[4 2]"
-	      EnableBusSupport	      on
-	      Port {
-		PortNumber		2
-		Name			"motorCommands"
-		RTWStorageClass		"Auto"
-		DataLoggingNameMode	"SignalName"
-	      }
-	    }
-	    Block {
-	      BlockType		      Terminator
-	      Name		      " Terminator "
-	      SID		      "647::21"
-	      Position		      [460, 241, 480, 259]
-	      ZOrder		      12
-	    }
-	    Block {
-	      BlockType		      Outport
-	      Name		      "motorCommands"
-	      SID		      "647::5"
-	      Position		      [460, 101, 480, 119]
-	      ZOrder		      -5
-	      IconDisplay	      "Port number"
-	    }
-	    Line {
-	      ZOrder		      105
-	      SrcBlock		      "height_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      106
-	      SrcBlock		      "y_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      2
-	    }
-	    Line {
-	      ZOrder		      107
-	      SrcBlock		      "x_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      3
-	    }
-	    Line {
-	      ZOrder		      108
-	      SrcBlock		      "yaw_controlled"
-	      SrcPort		      1
-	      DstBlock		      " SFunction "
-	      DstPort		      4
-	    }
-	    Line {
-	      Name		      "motorCommands"
-	      ZOrder		      109
-	      Labels		      [0, 0]
-	      SrcBlock		      " SFunction "
-	      SrcPort		      2
-	      DstBlock		      "motorCommands"
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      110
-	      SrcBlock		      " Demux "
-	      SrcPort		      1
-	      DstBlock		      " Terminator "
-	      DstPort		      1
-	    }
-	    Line {
-	      ZOrder		      111
-	      SrcBlock		      " SFunction "
-	      SrcPort		      1
-	      DstBlock		      " Demux "
-	      DstPort		      1
-	    }
-	  }
-	}
-	Block {
-	  BlockType		  Saturate
-	  Name			  "Saturation"
-	  SID			  "756"
-	  Ports			  [1, 1]
-	  Position		  [960, 455, 990, 485]
-	  ZOrder		  44
-	  InputPortMap		  "u0"
-	  UpperLimit		  "Pmax*ones(4,1)"
-	  LowerLimit		  "Pmin*ones(4,1)"
-	}
-	Block {
-	  BlockType		  Scope
-	  Name			  "Scope1"
-	  SID			  "794"
-	  Ports			  [1]
-	  Position		  [1080, 564, 1110, 596]
-	  ZOrder		  46
-	  Floating		  off
-	  Location		  [188, 365, 512, 604]
-	  Open			  off
-	  NumInputPorts		  "1"
-	  List {
-	    ListType		    AxesTitles
-	    axes1		    "%<SignalLabel>"
-	  }
-	  List {
-	    ListType		    ScopeGraphics
-	    FigureColor		    "[0.156862745098039 0.156862745098039 0.156862745098039]"
-	    AxesColor		    "[0 0 0]"
-	    AxesTickColor	    "[0.686274509803922 0.686274509803922 0.686274509803922]"
-	    LineColors		    "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]"
-	    LineStyles		    "-|-|-|-|-|-"
-	    LineWidths		    "[0.5 0.5 0.5 0.5 0.5 0.5]"
-	    MarkerStyles	    "none|none|none|none|none|none"
-	  }
-	  YMin			  "87500.00000"
-	  YMax			  "212500.00000"
-	  SaveName		  "ScopeData4"
-	  DataFormat		  "StructureWithTime"
-	  LimitDataPoints	  off
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum"
-	  SID			  "748"
-	  Ports			  [2, 1]
-	  Position		  [655, 340, 675, 360]
-	  ZOrder		  36
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum1"
-	  SID			  "749"
-	  Ports			  [2, 1]
-	  Position		  [655, 420, 675, 440]
-	  ZOrder		  37
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum2"
-	  SID			  "750"
-	  Ports			  [2, 1]
-	  Position		  [655, 500, 675, 520]
-	  ZOrder		  38
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  Sum
-	  Name			  "Sum3"
-	  SID			  "751"
-	  Ports			  [2, 1]
-	  Position		  [655, 580, 675, 600]
-	  ZOrder		  39
-	  ShowName		  off
-	  IconShape		  "round"
-	  Inputs		  "|++"
-	  InputSameDT		  off
-	  OutDataTypeStr	  "Inherit: Inherit via internal rule"
-	  SaturateOnIntegerOverflow off
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "height_controlled_o"
-	  SID			  "752"
-	  Position		  [605, 375, 635, 405]
-	  ZOrder		  40
-	  Value			  "height_controlled_o"
-	  SampleTime		  "5e-3"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "x_controlled_o"
-	  SID			  "754"
-	  Position		  [605, 535, 635, 565]
-	  ZOrder		  42
-	  Value			  "x_controlled_o"
-	  SampleTime		  "5e-3"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "y_controlled_o"
-	  SID			  "753"
-	  Position		  [605, 455, 635, 485]
-	  ZOrder		  41
-	  Value			  "y_controlled_o"
-	  SampleTime		  "5e-3"
-	}
-	Block {
-	  BlockType		  Constant
-	  Name			  "yaw_controlled_o"
-	  SID			  "755"
-	  Position		  [605, 620, 635, 650]
-	  ZOrder		  43
-	  Value			  "yaw_controlled_o"
-	  SampleTime		  "5e-3"
-	}
-	Block {
-	  BlockType		  Outport
-	  Name			  "Motor Commands"
-	  SID			  "578"
-	  Position		  [1055, 463, 1085, 477]
-	  ZOrder		  -2
-	  IconDisplay		  "Port number"
-	}
-	Line {
-	  ZOrder		  1
-	  SrcBlock		  "setpoints"
-	  SrcPort		  1
-	  DstBlock		  "Demux"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  30
-	  SrcBlock		  "euler_angles_filtered"
-	  SrcPort		  1
-	  DstBlock		  "Demux1"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  3
-	  SrcBlock		  "current_position"
-	  SrcPort		  1
-	  DstBlock		  "Demux2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  34
-	  SrcBlock		  "euler_rates"
-	  SrcPort		  1
-	  DstBlock		  "Demux4"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  27
-	  SrcBlock		  "Demux"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  28
-	  SrcBlock		  "Demux"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  29
-	  SrcBlock		  "Demux"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  40
-	  SrcBlock		  "Demux2"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  5
-	}
-	Line {
-	  ZOrder		  41
-	  SrcBlock		  "Demux2"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  6
-	}
-	Line {
-	  ZOrder		  42
-	  SrcBlock		  "Demux2"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  7
-	}
-	Line {
-	  ZOrder		  68
-	  SrcBlock		  "Controller"
-	  SrcPort		  2
-	  DstBlock		  "Sum1"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  69
-	  SrcBlock		  "Sum1"
-	  SrcPort		  1
-	  DstBlock		  "MATLAB Function"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  71
-	  SrcBlock		  "Sum2"
-	  SrcPort		  1
-	  DstBlock		  "MATLAB Function"
-	  DstPort		  3
-	}
-	Line {
-	  ZOrder		  72
-	  SrcBlock		  "Controller"
-	  SrcPort		  4
-	  DstBlock		  "Sum3"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  73
-	  SrcBlock		  "Sum3"
-	  SrcPort		  1
-	  DstBlock		  "MATLAB Function"
-	  DstPort		  4
-	}
-	Line {
-	  ZOrder		  74
-	  SrcBlock		  "Controller"
-	  SrcPort		  1
-	  DstBlock		  "Sum"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  75
-	  SrcBlock		  "Sum"
-	  SrcPort		  1
-	  DstBlock		  "MATLAB Function"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  77
-	  SrcBlock		  "y_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum1"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  78
-	  SrcBlock		  "x_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum2"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  79
-	  SrcBlock		  "yaw_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum3"
-	  DstPort		  2
-	}
-	Line {
-	  ZOrder		  80
-	  SrcBlock		  "MATLAB Function"
-	  SrcPort		  1
-	  DstBlock		  "Saturation"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  81
-	  SrcBlock		  "Saturation"
-	  SrcPort		  1
-	  Points		  [21, 0]
-	  Branch {
-	    ZOrder		    122
-	    Points		    [0, 110]
-	    DstBlock		    "Scope1"
-	    DstPort		    1
-	  }
-	  Branch {
-	    ZOrder		    121
-	    DstBlock		    "Motor Commands"
-	    DstPort		    1
-	  }
-	}
-	Line {
-	  ZOrder		  84
-	  SrcBlock		  "Demux1"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  8
-	}
-	Line {
-	  ZOrder		  86
-	  SrcBlock		  "Demux1"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  9
-	}
-	Line {
-	  ZOrder		  90
-	  SrcBlock		  "Demux4"
-	  SrcPort		  1
-	  DstBlock		  "Controller"
-	  DstPort		  11
-	}
-	Line {
-	  ZOrder		  91
-	  SrcBlock		  "Demux4"
-	  SrcPort		  2
-	  DstBlock		  "Controller"
-	  DstPort		  12
-	}
-	Line {
-	  ZOrder		  93
-	  SrcBlock		  "Demux4"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  13
-	}
-	Line {
-	  ZOrder		  94
-	  SrcBlock		  "Demux"
-	  SrcPort		  4
-	  DstBlock		  "Controller"
-	  DstPort		  4
-	}
-	Line {
-	  ZOrder		  95
-	  SrcBlock		  "Demux1"
-	  SrcPort		  3
-	  DstBlock		  "Controller"
-	  DstPort		  10
-	}
-	Line {
-	  ZOrder		  131
-	  SrcBlock		  "Controller"
-	  SrcPort		  3
-	  DstBlock		  "Sum2"
-	  DstPort		  1
-	}
-	Line {
-	  ZOrder		  133
-	  SrcBlock		  "height_controlled_o"
-	  SrcPort		  1
-	  Points		  [25, 0]
-	  DstBlock		  "Sum"
-	  DstPort		  2
-	}
-      }
-    }
-    Line {
-      ZOrder		      52
-      SrcBlock		      "Control System"
-      SrcPort		      1
-      DstBlock		      "Actuation"
-      DstPort		      1
-    }
-    Line {
-      ZOrder		      55
-      SrcBlock		      "Communication System"
-      SrcPort		      1
-      DstBlock		      "Control System"
-      DstPort		      1
-    }
-    Line {
-      ZOrder		      189
-      SrcBlock		      "Actuation"
-      SrcPort		      1
-      DstBlock		      "     Sensors   "
-      DstPort		      1
-    }
-    Line {
-      ZOrder		      191
-      SrcBlock		      "Actuation"
-      SrcPort		      3
-      DstBlock		      "     Sensors   "
-      DstPort		      3
-    }
-    Line {
-      ZOrder		      192
-      SrcBlock		      "Actuation"
-      SrcPort		      4
-      DstBlock		      "     Sensors   "
-      DstPort		      4
-    }
-    Line {
-      ZOrder		      193
-      SrcBlock		      "Actuation"
-      SrcPort		      5
-      DstBlock		      "     Sensors   "
-      DstPort		      5
-    }
-    Line {
-      ZOrder		      194
-      SrcBlock		      "Actuation"
-      SrcPort		      6
-      DstBlock		      "     Sensors   "
-      DstPort		      6
-    }
-    Line {
-      ZOrder		      195
-      SrcBlock		      "     Sensors   "
-      SrcPort		      3
-      Points		      [9, 0; 0, 210; -903, 0; 0, -160]
-      DstBlock		      "Control System"
-      DstPort		      4
-    }
-    Line {
-      ZOrder		      196
-      SrcBlock		      "     Sensors   "
-      SrcPort		      2
-      Points		      [16, 0; 0, 302; -924, 0; 0, -247]
-      DstBlock		      "Control System"
-      DstPort		      3
-    }
-    Line {
-      ZOrder		      190
-      SrcBlock		      "Actuation"
-      SrcPort		      2
-      DstBlock		      "     Sensors   "
-      DstPort		      2
-    }
-    Line {
-      ZOrder		      208
-      SrcBlock		      "     Sensors   "
-      SrcPort		      4
-      Points		      [2, 0; 0, 42; -903, 0; 0, -162]
-      DstBlock		      "Control System"
-      DstPort		      2
-    }
-  }
-}
-#Finite State Machines
-#
-#   Stateflow 80000005
-#
-#
-Stateflow {
-  machine {
-    id			    1
-    name		    "test_model_R2015A"
-    created		    "03-Nov-2016 18:34:53"
-    isLibrary		    0
-    firstTarget		    145
-    sfVersion		    80000005
-  }
-  chart {
-    id			    2
-    name		    "Actuation/Gravity\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 3 0 0]
-    firstTransition	    8
-    firstJunction	    7
-    viewObj		    2
-    machine		    1
-    ssIdHighWaterMark	    7
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    4
-    chartFileNumber	    1
-    disableImplicitCasting  1
-    eml {
-      name		      "gravity"
-    }
-  }
-  state {
-    id			    3
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    2
-    treeNode		    [2 0 0 0]
-    superState		    SUBCHART
-    subviewer		    2
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function E_Fg = gravity(m, g)\n\nE_Fg = [0; 0; m*g];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    4
-    ssIdNumber		    5
-    name		    "E_Fg"
-    linkNode		    [2 0 5]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    5
-    ssIdNumber		    6
-    name		    "m"
-    linkNode		    [2 4 6]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    6
-    ssIdNumber		    7
-    name		    "g"
-    linkNode		    [2 5 0]
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    7
-    position		    [23.5747 49.5747 7]
-    chart		    2
-    linkNode		    [2 0 0]
-    subviewer		    2
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    8
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      7
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    2
-    linkNode		    [2 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    2
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    9
-    name		    "Actuation/Gravity\n\n"
-    machine		    1
-    chart		    2
-  }
-  chart {
-    id			    10
-    name		    "Actuation/Lbe\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 11 0 0]
-    firstTransition	    16
-    firstJunction	    15
-    viewObj		    10
-    machine		    1
-    ssIdHighWaterMark	    11
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    12
-    chartFileNumber	    2
-    disableImplicitCasting  1
-    eml {
-      name		      "linear_body_earth_conversion"
-    }
-  }
-  state {
-    id			    11
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    10
-    treeNode		    [10 0 0 0]
-    superState		    SUBCHART
-    subviewer		    10
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function E_ro  = linear_body_earth_conversion(B_vo, euler_angles)\n\neuler_rates = zeros(3,1);\nE"
-      "_ro = zeros(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLeb = [cos(thet"
-      "a)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ..."
-      "\n       cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(p"
-      "hi)*cos(psi); ...\n           -sin(theta)    ,                sin(phi)*cos(theta)            ,                 c"
-      "os(phi)*cos(theta)           ];\n\nE_ro = Leb * B_vo;"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    12
-    ssIdNumber		    7
-    name		    "B_vo"
-    linkNode		    [10 0 13]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    13
-    ssIdNumber		    11
-    name		    "euler_angles"
-    linkNode		    [10 12 14]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    14
-    ssIdNumber		    9
-    name		    "E_ro"
-    linkNode		    [10 13 0]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    15
-    position		    [23.5747 49.5747 7]
-    chart		    10
-    linkNode		    [10 0 0]
-    subviewer		    10
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    16
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      15
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    10
-    linkNode		    [10 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    10
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    17
-    name		    "Actuation/Lbe\n\n\n\n\n\n"
-    machine		    1
-    chart		    10
-  }
-  chart {
-    id			    18
-    name		    "     Sensors   /3D Graphical Simulation1/MATLAB Function"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 19 0 0]
-    firstTransition	    23
-    firstJunction	    22
-    viewObj		    18
-    machine		    1
-    ssIdHighWaterMark	    5
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    20
-    chartFileNumber	    3
-    disableImplicitCasting  1
-    eml {
-      name		      "eigenaxis_ucart"
-    }
-  }
-  state {
-    id			    19
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    18
-    treeNode		    [18 0 0 0]
-    superState		    SUBCHART
-    subviewer		    18
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n    u(1) = 0.0001;\nend\n\nif abs(u(2)"
-      ")< 0.0001\n    u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n    u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) "
-      "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin("
-      "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = "
-      "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u("
-      "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n    \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; "
-      "C31-C13; C12-C21]/(2*sin(theta));\n    \ny = [e; theta];\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    20
-    ssIdNumber		    4
-    name		    "u"
-    linkNode		    [18 0 21]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    21
-    ssIdNumber		    5
-    name		    "y"
-    linkNode		    [18 20 0]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    22
-    position		    [23.5747 49.5747 7]
-    chart		    18
-    linkNode		    [18 0 0]
-    subviewer		    18
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    23
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      22
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    18
-    linkNode		    [18 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    18
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    24
-    name		    "     Sensors   /3D Graphical Simulation1/MATLAB Function"
-    machine		    1
-    chart		    18
-  }
-  chart {
-    id			    25
-    name		    "Actuation/ESC System"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 26 0 0]
-    firstTransition	    33
-    firstJunction	    32
-    viewObj		    25
-    machine		    1
-    ssIdHighWaterMark	    18
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    27
-    chartFileNumber	    4
-    disableImplicitCasting  1
-    eml {
-      name		      "ESC"
-    }
-  }
-  state {
-    id			    26
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    25
-    treeNode		    [25 0 0 0]
-    superState		    SUBCHART
-    subviewer		    25
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function Vb_eff   = ESC(rotor_duty_cycles, Pmin, Pmax, Vb)\n\nrotor_0_duty_cycle = rotor_duty_cyc"
-      "les(1);\nrotor_1_duty_cycle = rotor_duty_cycles(2);\nrotor_2_duty_cycle = rotor_duty_cycles(3);\nrotor_3_duty_cy"
-      "cle = rotor_duty_cycles(4);\n\n% Define u_Pi for each of the rotors, limiting it to be greater than 0\n% u_P0 = "
-      "(rotor_0_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u_P1 = (rotor_1_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u"
-      "_P2 = (rotor_2_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u_P3 = (rotor_3_duty_cycle/100 - Pmin) / (Pmax - Pmin)"
-      ";\nu_P0 = (rotor_0_duty_cycle - Pmin) / (Pmax - Pmin);\nu_P1 = (rotor_1_duty_cycle - Pmin) / (Pmax - Pmin);\nu_P"
-      "2 = (rotor_2_duty_cycle - Pmin) / (Pmax - Pmin);\nu_P3 = (rotor_3_duty_cycle - Pmin) / (Pmax - Pmin);\n\n\n% Det"
-      "ermine the effective battery voltage from each ESC\nVb_eff_0 = u_P0 * Vb;\nVb_eff_1 = u_P1 * Vb;\nVb_eff_2 = u_P"
-      "2 * Vb;\nVb_eff_3 = u_P3 * Vb;\n    \nVb_eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    27
-    ssIdNumber		    4
-    name		    "rotor_duty_cycles"
-    linkNode		    [25 0 28]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    28
-    ssIdNumber		    5
-    name		    "Vb_eff"
-    linkNode		    [25 27 29]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"1,4"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    29
-    ssIdNumber		    16
-    name		    "Pmin"
-    linkNode		    [25 28 30]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    30
-    ssIdNumber		    17
-    name		    "Pmax"
-    linkNode		    [25 29 31]
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    31
-    ssIdNumber		    18
-    name		    "Vb"
-    linkNode		    [25 30 0]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 2
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    32
-    position		    [23.5747 49.5747 7]
-    chart		    25
-    linkNode		    [25 0 0]
-    subviewer		    25
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    33
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      32
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    25
-    linkNode		    [25 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    25
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    34
-    name		    "Actuation/ESC System"
-    machine		    1
-    chart		    25
-  }
-  chart {
-    id			    35
-    name		    "Actuation/Motor System"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 36 0 0]
-    firstTransition	    47
-    firstJunction	    46
-    viewObj		    35
-    machine		    1
-    ssIdHighWaterMark	    16
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    37
-    chartFileNumber	    5
-    disableImplicitCasting  1
-    eml {
-      name		      "motor"
-    }
-  }
-  state {
-    id			    36
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    35
-    treeNode		    [35 0 0 0]
-    superState		    SUBCHART
-    subviewer		    35
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function angular_acceleration = motor(Vb_eff, angular_velocity, Rm, Kv, Kq, Kd, If, Jreq)\n\n% De"
-      "fine each motors effective battery voltage\nVb_eff_0 = Vb_eff(1);\nVb_eff_1 = Vb_eff(2);\nVb_eff_2 = Vb_eff(3);\n"
-      "Vb_eff_3 = Vb_eff(4);\n\n% Determine the angular velocity of each rotor from feedback\nw_0 = angular_velocity(1)"
-      ";\nw_1 = angular_velocity(2);\nw_2 = angular_velocity(3);\nw_3 = angular_velocity(4);\n\n% w_0 = (-1 + sqrt(1 - "
-      "4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_eff_0)))/2*Rm*Kv*Kq*Kd;\n% w_1 = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_"
-      "eff_1)))/2*Rm*Kv*Kq*Kd;\n% w_2 = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_eff_2)))/2*Rm*Kv*Kq*Kd;\n% w_3 ="
-      " (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_eff_3)))/2*Rm*Kv*Kq*Kd;\n% angular_velocity = [w_0, w_1, w_2, w_"
-      "3];\n\n% Determine angular acceleration of each rotor\nw_0_dot = 1/(Jreq*Rm*Kq) * Vb_eff_0 - 1/(Jreq*Rm*Kq*Kv) *"
-      " w_0 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_0^2;\nw_1_dot = 1/(Jreq*Rm*Kq) * Vb_eff_1 - 1/(Jreq*Rm*Kq*Kv) * w_1 - 1/(J"
-      "req*Kq)*If - (Kd/Jreq) * w_1^2;\nw_2_dot = 1/(Jreq*Rm*Kq) * Vb_eff_2 - 1/(Jreq*Rm*Kq*Kv) * w_2 - 1/(Jreq*Kq)*If "
-      "- (Kd/Jreq) * w_2^2;\nw_3_dot = 1/(Jreq*Rm*Kq) * Vb_eff_3 - 1/(Jreq*Rm*Kq*Kv) * w_3 - 1/(Jreq*Kq)*If - (Kd/Jreq)"
-      " * w_3^2;\n\n\n\nangular_acceleration = [w_0_dot, w_1_dot, w_2_dot, w_3_dot];  "
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    37
-    ssIdNumber		    4
-    name		    "Vb_eff"
-    linkNode		    [35 0 38]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    38
-    ssIdNumber		    16
-    name		    "angular_velocity"
-    linkNode		    [35 37 39]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    39
-    ssIdNumber		    7
-    name		    "angular_acceleration"
-    linkNode		    [35 38 40]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"1,4"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    40
-    ssIdNumber		    9
-    name		    "Rm"
-    linkNode		    [35 39 41]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 5
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    41
-    ssIdNumber		    10
-    name		    "Kv"
-    linkNode		    [35 40 42]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 4
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    42
-    ssIdNumber		    11
-    name		    "Kq"
-    linkNode		    [35 41 43]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 3
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    43
-    ssIdNumber		    12
-    name		    "Kd"
-    linkNode		    [35 42 44]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 2
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    44
-    ssIdNumber		    13
-    name		    "If"
-    linkNode		    [35 43 45]
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    45
-    ssIdNumber		    14
-    name		    "Jreq"
-    linkNode		    [35 44 0]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    46
-    position		    [23.5747 49.5747 7]
-    chart		    35
-    linkNode		    [35 0 0]
-    subviewer		    35
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    47
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      46
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    35
-    linkNode		    [35 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    35
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    48
-    name		    "Actuation/Motor System"
-    machine		    1
-    chart		    35
-  }
-  chart {
-    id			    49
-    name		    "Actuation/Rotor System\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 50 0 0]
-    firstTransition	    69
-    firstJunction	    68
-    viewObj		    49
-    machine		    1
-    ssIdHighWaterMark	    30
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    51
-    chartFileNumber	    6
-    disableImplicitCasting  1
-    eml {
-      name		      "rotor"
-    }
-  }
-  state {
-    id			    50
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    49
-    treeNode		    [49 0 0 0]
-    superState		    SUBCHART
-    subviewer		    49
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [B_omega_dot, B_vo_dot]= rotor(angular_acceleration, angular_velocity, B_Fg, B_omega, B_"
-      "vo, m, Kt, Kd, rhx, rhy, rhz, Jreq, Jxx, Jyy, Jzz)\n\n%B_vo_dot = zeros(3,1);\n%B_omega_dot = zeros(3,1);\n\n% C"
-      "reate J vector\nJ = [Jxx,  0 ,  0 ; ...\n      0 , Jyy,  0 ; ...\n      0 ,  0 , Jzz;];\n\n% Create r_hi vector\n"
-      "% rh_0 = [-rhx; rhy; rhz];\n% rh_1 = [rhx; rhy; rhz];\n% rh_2 = [-rhx; -rhy; rhz];\n% rh_3 = [rhx; -rhy; rhz];\n"
-      "rh_0 = [-rhx; rhy; -rhz];\nrh_1 = [rhx; rhy; -rhz];\nrh_2 = [-rhx; -rhy; -rhz];\nrh_3 = [rhx; -rhy; -rhz];\n\n% "
-      "Define vector from body frame origin to center of mass\nbr_oc = [0; 0; 0];\n\n% Define 3x3 Identity Matrix\nI = "
-      "eye(3);\n\n% Create gamma vectors\ngamma_Ti = [0; 0; -1];\n%gamma_omega_03 = [0; 0; -1];  %Rotors 0 and 3 use th"
-      "is gamma_omega vector\n%gamma_omega_12 = [0; 0; 1]; %Rotors 1 and 2 use this gamma_omega vector\ngamma_omega_03 "
-      "= [0; 0; 1];  %Rotors 0 and 3 use this gamma_omega vector\ngamma_omega_12 = [0; 0; -1]; %Rotors 1 and 2 use this"
-      " gamma_omega vector\n\n% Define angular velocities for each rotor\nw_0 = angular_velocity(1);\nw_1 = angular_vel"
-      "ocity(2);\nw_2 = angular_velocity(3);\nw_3 = angular_velocity(4);\n\n% Define angular acceleration for each roto"
-      "r\nw_0_dot = angular_acceleration(1);\nw_1_dot = angular_acceleration(2);\nw_2_dot = angular_acceleration(3);\nw"
-      "_3_dot = angular_acceleration(4);\n\n% Define the rotor force in the z-direction from each rotor\nB_Fr_0 = Kt * "
-      "w_0 * w_0 * gamma_Ti;\nB_Fr_1 = Kt * w_1 * w_1 * gamma_Ti;\nB_Fr_2 = Kt * w_2 * w_2 * gamma_Ti;\nB_Fr_3 = Kt * w"
-      "_3 * w_3 * gamma_Ti;\n\n% Sum up the rotor forces in the z-direction from each vector to get the\n% total body f"
-      "orce in the z-direction\nB_Fr = B_Fr_0 + B_Fr_1 + B_Fr_2 + B_Fr_3;\n\n% Define the in-plane drag and induced tor"
-      "que produced by each rotor\n B_Q_d0 = -1 * Kd * w_0 * w_0 * gamma_omega_03;\n B_Q_d1 = -1 * Kd * w_1 * w_1 * gam"
-      "ma_omega_12;\n B_Q_d2 = -1 * Kd * w_2 * w_2 * gamma_omega_12;\n B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;\n"
-      "\n% Sum up the total in-plane drag and induced torque to get the total\n% in-plane drag and induced torque on th"
-      "e body\nB_Q_d = B_Q_d0 + B_Q_d1 + B_Q_d2 + B_Q_d3;\n\n% Define the force lever arm torque created from the force"
-      " produced by each\n% rotor in the z-direction\nB_Q_F0 = cross( rh_0, B_Fr_0 );\nB_Q_F1 = cross( rh_1, B_Fr_1 );\n"
-      "B_Q_F2 = cross( rh_2, B_Fr_2 );\nB_Q_F3 = cross( rh_3, B_Fr_3 );\n\nB_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;\n"
-      "\n%Define the change in angular momentum torque produced by each rotor \nB_Q_L0 = -1 * Jreq * ( cross(B_omega, w"
-      "_0 * gamma_omega_03) + w_0_dot * gamma_omega_03 );\nB_Q_L1 = -1 * Jreq * ( cross(B_omega, w_1 * gamma_omega_12) "
-      "+ w_1_dot * gamma_omega_12 ); \nB_Q_L2 = -1 * Jreq * ( cross(B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_om"
-      "ega_12 ); \nB_Q_L3 = -1 * Jreq * ( cross(B_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );\n\n% Sum u"
-      "p the total change in angular momentum torque produced by each rotor\nB_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;"
-      "\n\n% Define the total rotor system torque as the sum of the in-plane drag and\n% induced torque, force lever ar"
-      "m torque, and change in angular momentum\n% torques\nB_Q = B_Q_d + B_Q_F + B_Q_L;\n\n% Define the body forces in"
-      " the z-direction from each vector to get the\n% total body force in the z-direction\nB_F = B_Fr + B_Fg; \n\n% De"
-      "fine the body frame linear velocities\nB_vo_dot = (m*I)^(-1) * ( B_F - cross( B_omega, m*(B_vo + cross(B_omega, "
-      "br_oc)) ) );\n\n% Define the body frame angular velocities\nB_omega_dot = J ^(-1) * ( B_Q - cross(B_omega, J * B"
-      "_omega) - cross(br_oc, B_F) );\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    51
-    ssIdNumber		    6
-    name		    "B_omega_dot"
-    linkNode		    [49 0 52]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    52
-    ssIdNumber		    10
-    name		    "angular_acceleration"
-    linkNode		    [49 51 53]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    53
-    ssIdNumber		    11
-    name		    "angular_velocity"
-    linkNode		    [49 52 54]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    54
-    ssIdNumber		    30
-    name		    "B_Fg"
-    linkNode		    [49 53 55]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    55
-    ssIdNumber		    8
-    name		    "B_omega"
-    linkNode		    [49 54 56]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    56
-    ssIdNumber		    5
-    name		    "B_vo_dot"
-    linkNode		    [49 55 57]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    57
-    ssIdNumber		    7
-    name		    "B_vo"
-    linkNode		    [49 56 58]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    58
-    ssIdNumber		    12
-    name		    "m"
-    linkNode		    [49 57 59]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 6
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    59
-    ssIdNumber		    14
-    name		    "Kt"
-    linkNode		    [49 58 60]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 5
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    60
-    ssIdNumber		    13
-    name		    "Kd"
-    linkNode		    [49 59 61]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 4
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    61
-    ssIdNumber		    15
-    name		    "rhx"
-    linkNode		    [49 60 62]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 7
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    62
-    ssIdNumber		    16
-    name		    "rhy"
-    linkNode		    [49 61 63]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 8
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    63
-    ssIdNumber		    17
-    name		    "rhz"
-    linkNode		    [49 62 64]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 9
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    64
-    ssIdNumber		    18
-    name		    "Jreq"
-    linkNode		    [49 63 65]
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    65
-    ssIdNumber		    19
-    name		    "Jxx"
-    linkNode		    [49 64 66]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 1
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    66
-    ssIdNumber		    20
-    name		    "Jyy"
-    linkNode		    [49 65 67]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 2
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    67
-    ssIdNumber		    21
-    name		    "Jzz"
-    linkNode		    [49 66 0]
-    scope		    PARAMETER_DATA
-    paramIndexForInitFromWorkspace 3
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    68
-    position		    [23.5747 49.5747 7]
-    chart		    49
-    linkNode		    [49 0 0]
-    subviewer		    49
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    69
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      68
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    49
-    linkNode		    [49 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    49
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    70
-    name		    "Actuation/Rotor System\n\n\n\n\n\n\n\n"
-    machine		    1
-    chart		    49
-  }
-  chart {
-    id			    71
-    name		    "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 72 0 0]
-    firstTransition	    77
-    firstJunction	    76
-    viewObj		    71
-    machine		    1
-    ssIdHighWaterMark	    6
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    73
-    chartFileNumber	    7
-    disableImplicitCasting  1
-    eml {
-      name		      "angular_body_earth_conversion"
-    }
-  }
-  state {
-    id			    72
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    71
-    treeNode		    [71 0 0 0]
-    superState		    SUBCHART
-    subviewer		    71
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function euler_rates = angular_body_earth_conversion(B_omega, euler_angles)\n\neuler_rates = zero"
-      "s(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta"
-      "); ...\n       0,     cos(phi)       ,        -sin(phi)   ; ...\n       0,  sin(phi)/cos(theta), cos(phi)/cos(th"
-      "eta)];\n\n   \neuler_rates = Aeb * B_omega;\n  "
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    73
-    ssIdNumber		    4
-    name		    "B_omega"
-    linkNode		    [71 0 74]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    74
-    ssIdNumber		    5
-    name		    "euler_rates"
-    linkNode		    [71 73 75]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    75
-    ssIdNumber		    6
-    name		    "euler_angles"
-    linkNode		    [71 74 0]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    76
-    position		    [23.5747 49.5747 7]
-    chart		    71
-    linkNode		    [71 0 0]
-    subviewer		    71
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    77
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      76
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    71
-    linkNode		    [71 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    71
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    78
-    name		    "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    machine		    1
-    chart		    71
-  }
-  chart {
-    id			    79
-    name		    "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 80 0 0]
-    firstTransition	    87
-    firstJunction	    86
-    viewObj		    79
-    machine		    1
-    ssIdHighWaterMark	    13
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    81
-    chartFileNumber	    8
-    disableImplicitCasting  1
-    eml {
-      name		      "linear_earth_body_conversion"
-    }
-  }
-  state {
-    id			    80
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    79
-    treeNode		    [79 0 0 0]
-    superState		    SUBCHART
-    subviewer		    79
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [B_Fg, B_g]  = linear_earth_body_conversion(E_Fg, euler_angles, m)\n\nphi = euler_angles"
-      "(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLbe = [             cos(theta)*cos(psi)              ,"
-      "          cos(theta)*sin(psi)                  ,     -sin(theta)    ; ...\n       sin(phi)*sin(theta)*cos(psi)-c"
-      "os(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...\n       cos(phi)*sin("
-      "theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];\n\nB_Fg"
-      " = Lbe * E_Fg;\n\nB_g = B_Fg/m;"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    81
-    ssIdNumber		    7
-    name		    "E_Fg"
-    linkNode		    [79 0 82]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    82
-    ssIdNumber		    11
-    name		    "euler_angles"
-    linkNode		    [79 81 83]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"3"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    83
-    ssIdNumber		    9
-    name		    "B_Fg"
-    linkNode		    [79 82 84]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"3"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    84
-    ssIdNumber		    12
-    name		    "B_g"
-    linkNode		    [79 83 85]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    85
-    ssIdNumber		    13
-    name		    "m"
-    linkNode		    [79 84 0]
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    86
-    position		    [23.5747 49.5747 7]
-    chart		    79
-    linkNode		    [79 0 0]
-    subviewer		    79
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    87
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      86
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    79
-    linkNode		    [79 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    79
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    88
-    name		    "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
-    machine		    1
-    chart		    79
-  }
-  chart {
-    id			    89
-    name		    "     Sensors   /Complimentary Filter\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 90 0 0]
-    firstTransition	    96
-    firstJunction	    95
-    viewObj		    89
-    visible		    1
-    machine		    1
-    subviewS {
-    }
-    ssIdHighWaterMark	    16
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    91
-    chartFileNumber	    9
-    disableImplicitCasting  1
-    eml {
-      name		      "complimentaryFilter"
-    }
-  }
-  state {
-    id			    90
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    89
-    treeNode		    [89 0 0 0]
-    superState		    SUBCHART
-    subviewer		    89
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "%function euler_angles_IMU  = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro, pre"
-      "v_euler_angles_IMU)\nfunction euler_angles_IMU  = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro"
-      ")\n\n% LOOP_TIME = 5*10^-3;\n% \n% prev_phi = prev_euler_angles_IMU(1);\n% prev_theta = prev_euler_angles_IMU(2)"
-      ";\n% \n% phi_dot_gyro = euler_angles_gyro(1);\n% theta_dot_gyro = euler_angles_gyro(2);\n\n% phi = 0.98 * ( prev"
-      "_phi + phi_dot_gyro * LOOP_TIME ) + 0.02 * accel_roll;\n% theta = 0.98 * ( prev_theta + theta_dot_gyro * LOOP_TI"
-      "ME) + 0.02 * accel_pitch;\nk_gyro = 0.98; \nk_accel = 1-k_gyro; \n\nphi = k_gyro * ( euler_angles_gyro(1) ) + k_"
-      "accel * accel_roll;\ntheta = k_gyro * ( euler_angles_gyro(2) ) + k_accel * accel_pitch;\n\neuler_angles_IMU = [p"
-      "hi; theta];\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    91
-    ssIdNumber		    4
-    name		    "accel_pitch"
-    linkNode		    [89 0 92]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    92
-    ssIdNumber		    13
-    name		    "accel_roll"
-    linkNode		    [89 91 93]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    93
-    ssIdNumber		    5
-    name		    "euler_angles_IMU"
-    linkNode		    [89 92 94]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"[2,1]"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    94
-    ssIdNumber		    6
-    name		    "euler_angles_gyro"
-    linkNode		    [89 93 0]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    95
-    position		    [23.5747 49.5747 7]
-    chart		    89
-    linkNode		    [89 0 0]
-    subviewer		    89
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    96
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      95
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    89
-    linkNode		    [89 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    89
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    97
-    name		    "     Sensors   /Complimentary Filter\n\n\n\n\n\n\n\n"
-    machine		    1
-    chart		    89
-  }
-  chart {
-    id			    98
-    name		    "     Sensors   /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 99 0 0]
-    firstTransition	    109
-    firstJunction	    108
-    viewObj		    98
-    machine		    1
-    ssIdHighWaterMark	    15
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    100
-    chartFileNumber	    10
-    disableImplicitCasting  1
-    eml {
-      name		      "idealIMU"
-    }
-  }
-  state {
-    id			    99
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    98
-    treeNode		    [98 0 0 0]
-    superState		    SUBCHART
-    subviewer		    98
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [accelReading,gyroReading] = idealIMU(B_vo_dot, B_vo, B_Omega, B_g, r_oc, g)\n%#codegen\n"
-      "\na = B_vo_dot + cross(B_Omega,B_vo) ; % body frame acceleration \n\naccelReading = (a - B_g)/g ; % acceleromete"
-      "r reading (ideal)\n\ngyroReading = B_Omega ; % gyroscope reading (ideal) \n\nend\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    100
-    ssIdNumber		    4
-    name		    "B_vo_dot"
-    linkNode		    [98 0 101]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    101
-    ssIdNumber		    9
-    name		    "B_vo"
-    linkNode		    [98 100 102]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    102
-    ssIdNumber		    5
-    name		    "accelReading"
-    linkNode		    [98 101 103]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    103
-    ssIdNumber		    6
-    name		    "B_Omega"
-    linkNode		    [98 102 104]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    104
-    ssIdNumber		    7
-    name		    "B_g"
-    linkNode		    [98 103 105]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    105
-    ssIdNumber		    8
-    name		    "gyroReading"
-    linkNode		    [98 104 106]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    106
-    ssIdNumber		    10
-    name		    "r_oc"
-    linkNode		    [98 105 107]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    107
-    ssIdNumber		    12
-    name		    "g"
-    linkNode		    [98 106 0]
-    scope		    PARAMETER_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    108
-    position		    [23.5747 49.5747 7]
-    chart		    98
-    linkNode		    [98 0 0]
-    subviewer		    98
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    109
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      108
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    98
-    linkNode		    [98 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    98
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    110
-    name		    "     Sensors   /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n"
-    machine		    1
-    chart		    98
-  }
-  chart {
-    id			    111
-    name		    "     Sensors   /3D Graphical Simulation/MATLAB Function"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 112 0 0]
-    firstTransition	    116
-    firstJunction	    115
-    viewObj		    111
-    machine		    1
-    ssIdHighWaterMark	    5
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    113
-    chartFileNumber	    11
-    disableImplicitCasting  1
-    eml {
-      name		      "eigenaxis_ucart"
-    }
-  }
-  state {
-    id			    112
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    111
-    treeNode		    [111 0 0 0]
-    superState		    SUBCHART
-    subviewer		    111
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n    u(1) = 0.0001;\nend\n\nif abs(u(2)"
-      ")< 0.0001\n    u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n    u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) "
-      "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin("
-      "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = "
-      "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u("
-      "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n    \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; "
-      "C31-C13; C12-C21]/(2*sin(theta));\n    \ny = [e; theta];\n\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    113
-    ssIdNumber		    4
-    name		    "u"
-    linkNode		    [111 0 114]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    114
-    ssIdNumber		    5
-    name		    "y"
-    linkNode		    [111 113 0]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    115
-    position		    [23.5747 49.5747 7]
-    chart		    111
-    linkNode		    [111 0 0]
-    subviewer		    111
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    116
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      115
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    111
-    linkNode		    [111 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    111
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    117
-    name		    "     Sensors   /3D Graphical Simulation/MATLAB Function"
-    machine		    1
-    chart		    111
-  }
-  chart {
-    id			    118
-    name		    "     Sensors   /Aeb\n\n\n\n\n\n\n\n\n\n"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 119 0 0]
-    firstTransition	    124
-    firstJunction	    123
-    viewObj		    118
-    machine		    1
-    ssIdHighWaterMark	    6
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    120
-    chartFileNumber	    12
-    disableImplicitCasting  1
-    eml {
-      name		      "angular_body_earth_conversion"
-    }
-  }
-  state {
-    id			    119
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    118
-    treeNode		    [118 0 0 0]
-    superState		    SUBCHART
-    subviewer		    118
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_IMU)\n\nphi ="
-      " euler_angles_IMU(1);\ntheta = euler_angles_IMU(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta); ...\n"
-      "       0,     cos(phi)       ,        -sin(phi)   ; ...\n       0,  sin(phi)/cos(theta), cos(phi)/cos(theta)];\n"
-      "\n   \neuler_rates_IMU = Aeb * gyro_reading;\n  "
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    120
-    ssIdNumber		    4
-    name		    "gyro_reading"
-    linkNode		    [118 0 121]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    121
-    ssIdNumber		    5
-    name		    "euler_rates_IMU"
-    linkNode		    [118 120 122]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"[3,1]"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    122
-    ssIdNumber		    6
-    name		    "euler_angles_IMU"
-    linkNode		    [118 121 0]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    123
-    position		    [23.5747 49.5747 7]
-    chart		    118
-    linkNode		    [118 0 0]
-    subviewer		    118
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    124
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      123
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    118
-    linkNode		    [118 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    118
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    125
-    name		    "     Sensors   /Aeb\n\n\n\n\n\n\n\n\n\n"
-    machine		    1
-    chart		    118
-  }
-  chart {
-    id			    126
-    name		    "     Sensors   /Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 127 0 0]
-    firstTransition	    133
-    firstJunction	    132
-    viewObj		    126
-    machine		    1
-    ssIdHighWaterMark	    10
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    128
-    chartFileNumber	    13
-    disableImplicitCasting  1
-    eml {
-      name		      "getPitchAndRoll"
-    }
-  }
-  state {
-    id			    127
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    126
-    treeNode		    [126 0 0 0]
-    superState		    SUBCHART
-    subviewer		    126
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function [accel_pitch, accel_roll] = getPitchAndRoll(accel_reading, accel_roll_prev)\n\nmag = nor"
-      "m(accel_reading);\n\nx_accel = accel_reading(1)/mag;\ny_accel = accel_reading(2)/mag;\nz_accel = accel_reading(3"
-      ")/mag;\n\naccel_pitch = atan(x_accel/sqrt(y_accel^2 + z_accel^2));\n%unwrapped_pitch = unwrap([accel_pitch_prev "
-      "accel_pitch]);\n%accel_pitch = unwrapped_pitch(2);\n\naccel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^"
-      "2 + (1/100)*x_accel^2)) );\nunwrapped_roll = unwrap([accel_roll_prev accel_roll]);\naccel_roll = unwrapped_roll("
-      "2); \n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    128
-    ssIdNumber		    4
-    name		    "accel_reading"
-    linkNode		    [126 0 129]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    129
-    ssIdNumber		    5
-    name		    "accel_pitch"
-    linkNode		    [126 128 130]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    130
-    ssIdNumber		    6
-    name		    "accel_roll"
-    linkNode		    [126 129 131]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    131
-    ssIdNumber		    7
-    name		    "accel_roll_prev"
-    linkNode		    [126 130 0]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    132
-    position		    [23.5747 49.5747 7]
-    chart		    126
-    linkNode		    [126 0 0]
-    subviewer		    126
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    133
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      132
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    126
-    linkNode		    [126 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    126
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    134
-    name		    "     Sensors   /Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1"
-    machine		    1
-    chart		    126
-  }
-  chart {
-    id			    135
-    name		    "Control System/MATLAB Function"
-    windowPosition	    [422 539.941 189 413]
-    viewLimits		    [0 156.75 0 153.75]
-    screen		    [1 1 3600 1200 1.180555555555556]
-    treeNode		    [0 136 0 0]
-    firstTransition	    143
-    firstJunction	    142
-    viewObj		    135
-    visible		    1
-    machine		    1
-    subviewS {
-    }
-    ssIdHighWaterMark	    11
-    decomposition	    CLUSTER_CHART
-    type		    EML_CHART
-    firstData		    137
-    chartFileNumber	    14
-    disableImplicitCasting  1
-    eml {
-      name		      "signal_mixer"
-    }
-  }
-  state {
-    id			    136
-    labelString		    "eML_blk_kernel()"
-    position		    [18 64.5 118 66]
-    fontSize		    12
-    chart		    135
-    treeNode		    [135 0 0 0]
-    superState		    SUBCHART
-    subviewer		    135
-    ssIdNumber		    1
-    type		    FUNC_STATE
-    decomposition	    CLUSTER_STATE
-    eml {
-      isEML		      1
-      script		      "function motorCommands  = signal_mixer(height_controlled, y_controlled, x_controlled, yaw_control"
-      "led)\n\ncontroller_outputs = [ height_controlled; x_controlled; y_controlled; yaw_controlled ];\nsignal_mixer = "
-      "[ 1, -1, -1, -1; ... \n                 1,  1, -1,  1; ...\n                 1, -1,  1,  1; ...\n               "
-      "  1,  1,  1, -1 ];\n\n% signal_mixer = [ 1,  1, -1, -1; ... \n%                  1, -1, -1,  1; ...\n%          "
-      "        1,  1,  1,  1; ...\n%                  1, -1,  1, -1 ];\n\nmotorCommands = signal_mixer * controller_out"
-      "puts;\n"
-      editorLayout	      "100 M4x1[10 5 700 500]"
-    }
-  }
-  data {
-    id			    137
-    ssIdNumber		    4
-    name		    "height_controlled"
-    linkNode		    [135 0 138]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    138
-    ssIdNumber		    7
-    name		    "y_controlled"
-    linkNode		    [135 137 139]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    139
-    ssIdNumber		    5
-    name		    "motorCommands"
-    linkNode		    [135 138 140]
-    scope		    OUTPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_NO
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    140
-    ssIdNumber		    6
-    name		    "x_controlled"
-    linkNode		    [135 139 141]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  data {
-    id			    141
-    ssIdNumber		    8
-    name		    "yaw_controlled"
-    linkNode		    [135 140 0]
-    scope		    INPUT_DATA
-    machine		    1
-    props {
-      array {
-	size			"-1"
-      }
-      type {
-	method			SF_INHERITED_TYPE
-	primitive		SF_DOUBLE_TYPE
-	isSigned		1
-	wordLength		"16"
-      }
-      complexity	      SF_COMPLEX_INHERITED
-      frame		      SF_FRAME_INHERITED
-    }
-    dataType		    "Inherit: Same as Simulink"
-  }
-  junction {
-    id			    142
-    position		    [23.5747 49.5747 7]
-    chart		    135
-    linkNode		    [135 0 0]
-    subviewer		    135
-    ssIdNumber		    3
-    type		    CONNECTIVE_JUNCTION
-  }
-  transition {
-    id			    143
-    labelString		    "{eML_blk_kernel();}"
-    labelPosition	    [28.125 13.875 102.544 14.964]
-    fontSize		    12
-    src {
-      intersection	      [0 0 1 0 23.5747 14.625 0 0]
-    }
-    dst {
-      id		      142
-      intersection	      [1 0 -1 0 23.5747 42.5747 0 0]
-    }
-    midPoint		    [23.5747 24.9468]
-    chart		    135
-    linkNode		    [135 0 0]
-    dataLimits		    [21.175 25.975 14.625 42.575]
-    subviewer		    135
-    drawStyle		    SMART
-    slide {
-      sticky		      BOTH_STICK
-    }
-    executionOrder	    1
-    ssIdNumber		    2
-  }
-  instance {
-    id			    144
-    name		    "Control System/MATLAB Function"
-    machine		    1
-    chart		    135
-  }
-  target {
-    id			    145
-    name		    "sfun"
-    description		    "Default Simulink S-Function Target."
-    machine		    1
-    linkNode		    [1 0 0]
-  }
-}
diff --git a/controls/model/test_model_R2015Ax.slx b/controls/model/test_model_R2015Ax.slx
deleted file mode 100644
index feb8b73e27a6546344f8e37555adce78811d6436..0000000000000000000000000000000000000000
Binary files a/controls/model/test_model_R2015Ax.slx and /dev/null differ
diff --git a/controls/model/weights_modern.mat b/controls/model/weights_modern.mat
new file mode 100644
index 0000000000000000000000000000000000000000..bfe32c8a1f2fe48728727b545f23d9d571889c69
Binary files /dev/null and b/controls/model/weights_modern.mat differ
diff --git a/controls/model/weights_old_quad.mat b/controls/model/weights_old_quad.mat
new file mode 100644
index 0000000000000000000000000000000000000000..2c6b3c2ba627676b72966bf6caba2c299981a90e
Binary files /dev/null and b/controls/model/weights_old_quad.mat differ
diff --git a/controls/model/weights_rich.mat b/controls/model/weights_rich.mat
new file mode 100644
index 0000000000000000000000000000000000000000..f0d4f575a2f0a580a918891f9521bb5158525a93
Binary files /dev/null and b/controls/model/weights_rich.mat differ
diff --git a/documentation/images/simulink_lqr_control.png b/documentation/images/simulink_lqr_control.png
new file mode 100644
index 0000000000000000000000000000000000000000..b9773c67678079ae49e3ba58aa3b4a9507c01c34
Binary files /dev/null and b/documentation/images/simulink_lqr_control.png differ
diff --git a/documentation/images/simulink_lqr_sensor.png b/documentation/images/simulink_lqr_sensor.png
new file mode 100644
index 0000000000000000000000000000000000000000..a1ab30ecc1774ab7014f806f0c57274287ff3e59
Binary files /dev/null and b/documentation/images/simulink_lqr_sensor.png differ
diff --git a/documentation/images/simulink_lqr_top.png b/documentation/images/simulink_lqr_top.png
new file mode 100644
index 0000000000000000000000000000000000000000..c2788ab123be6355915c0ee06c7e0c93fc48588f
Binary files /dev/null and b/documentation/images/simulink_lqr_top.png differ