diff --git a/.gitignore b/.gitignore
index 7ed439565d369ace3cc8f64db96e8a422bd6ebf0..50624b5782c83bc746bbdca584534418d5caf105 100644
--- a/.gitignore
+++ b/.gitignore
@@ -4,5 +4,26 @@ groundStation/gui/build*
 .vscode
 /crazyflie_hardware/sd_test_stand/sd_test_stand-backups/*
 /crazyflie_hardware/sd_test_stand_nano/sd_test_stand_nano-backups/*
-controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/slprj/
-*/.idea/
+
+##---------------------------------------------------
+## Remove autosaves generated by the Matlab editor
+## We have git for backups!
+##---------------------------------------------------
+
+# Windows default autosave extension
+*.asv
+
+# OSX / *nix default autosave extension
+*.m~
+
+# Compiled MEX binaries (all platforms)
+*.mex*
+
+# Simulink Code Generation
+slprj/
+
+# Session info
+octave-workspace
+
+# Simulink autosave extension
+.autosave
\ No newline at end of file
diff --git a/.idea/MicroCART.iml b/.idea/MicroCART.iml
index caa57a1c754d3b46004608ce57c9fd2e505127df..82a7a013589e69a2c05199da38b46c00038283b6 100644
--- a/.idea/MicroCART.iml
+++ b/.idea/MicroCART.iml
@@ -5,6 +5,13 @@
     <orderEntry type="inheritedJdk" />
     <orderEntry type="sourceFolder" forTests="false" />
   </component>
+  <component name="PackageRequirementsSettings">
+    <option name="removeUnused" value="true" />
+  </component>
+  <component name="PyDocumentationSettings">
+    <option name="format" value="PLAIN" />
+    <option name="myDocStringFormat" value="Plain" />
+  </component>
   <component name="TemplatesService">
     <option name="TEMPLATE_CONFIGURATION" value="Jinja2" />
     <option name="TEMPLATE_FOLDERS">
diff --git a/.idea/inspectionProfiles/Project_Default.xml b/.idea/inspectionProfiles/Project_Default.xml
new file mode 100644
index 0000000000000000000000000000000000000000..88ae6cbe302141eee1ec2a0ab61878958b155eb4
--- /dev/null
+++ b/.idea/inspectionProfiles/Project_Default.xml
@@ -0,0 +1,92 @@
+<component name="InspectionProjectProfileManager">
+  <profile version="1.0">
+    <option name="myName" value="Project Default" />
+    <inspection_tool class="DuplicatedCode" enabled="true" level="WEAK WARNING" enabled_by_default="true">
+      <Languages>
+        <language minSize="67" name="Python" />
+      </Languages>
+    </inspection_tool>
+    <inspection_tool class="HttpUrlsUsage" enabled="true" level="WEAK WARNING" enabled_by_default="true">
+      <option name="ignoredUrls">
+        <list>
+          <option value="http://localhost" />
+          <option value="http://127.0.0.1" />
+          <option value="http://0.0.0.0" />
+          <option value="http://www.w3.org/" />
+          <option value="http://json-schema.org/draft" />
+          <option value="http://java.sun.com/" />
+          <option value="http://xmlns.jcp.org/" />
+          <option value="http://javafx.com/javafx/" />
+          <option value="http://javafx.com/fxml" />
+          <option value="http://maven.apache.org/xsd/" />
+          <option value="http://maven.apache.org/POM/" />
+          <option value="http://www.springframework.org/schema/" />
+          <option value="http://www.springframework.org/tags" />
+          <option value="http://www.springframework.org/security/tags" />
+          <option value="http://www.thymeleaf.org" />
+          <option value="http://www.jboss.org/j2ee/schema/" />
+          <option value="http://www.jboss.com/xml/ns/" />
+          <option value="http://www.ibm.com/webservices/xsd" />
+          <option value="http://activemq.apache.org/schema/" />
+          <option value="http://schema.cloudfoundry.org/spring/" />
+          <option value="http://schemas.xmlsoap.org/" />
+          <option value="http://cxf.apache.org/schemas/" />
+          <option value="http://primefaces.org/ui" />
+          <option value="http://tiles.apache.org/" />
+          <option value="http://api.velocityweather.com" />
+        </list>
+      </option>
+    </inspection_tool>
+    <inspection_tool class="PyChainedComparisonsInspection" enabled="true" level="WEAK WARNING" enabled_by_default="true">
+      <option name="ignoreConstantInTheMiddle" value="true" />
+    </inspection_tool>
+    <inspection_tool class="PyPackageRequirementsInspection" enabled="true" level="WARNING" enabled_by_default="true">
+      <option name="ignoredPackages">
+        <value>
+          <list size="6">
+            <item index="0" class="java.lang.String" itemvalue="terminado" />
+            <item index="1" class="java.lang.String" itemvalue="srtm4" />
+            <item index="2" class="java.lang.String" itemvalue="matplotlib" />
+            <item index="3" class="java.lang.String" itemvalue="numpy" />
+            <item index="4" class="java.lang.String" itemvalue="scipy" />
+            <item index="5" class="java.lang.String" itemvalue="numba" />
+          </list>
+        </value>
+      </option>
+    </inspection_tool>
+    <inspection_tool class="PyPep8Inspection" enabled="true" level="WEAK WARNING" enabled_by_default="true">
+      <option name="ignoredErrors">
+        <list>
+          <option value="E127" />
+          <option value="E266" />
+        </list>
+      </option>
+    </inspection_tool>
+    <inspection_tool class="PyPep8NamingInspection" enabled="true" level="WEAK WARNING" enabled_by_default="true">
+      <option name="ignoredErrors">
+        <list>
+          <option value="N802" />
+          <option value="N803" />
+          <option value="N806" />
+          <option value="N801" />
+          <option value="N813" />
+        </list>
+      </option>
+    </inspection_tool>
+    <inspection_tool class="PyUnresolvedReferencesInspection" enabled="true" level="WARNING" enabled_by_default="true">
+      <option name="ignoredIdentifiers">
+        <list>
+          <option value="tuple.twinx" />
+          <option value="super.configureMainData" />
+          <option value="list.tkraise" />
+          <option value="list.cont" />
+          <option value="list.grid" />
+          <option value="parent_dir" />
+          <option value="loop_filepaths" />
+          <option value="list.__getitem__" />
+          <option value="int.value" />
+        </list>
+      </option>
+    </inspection_tool>
+  </profile>
+</component>
\ No newline at end of file
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/Copy_of_measured_flight_path.mat b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/Copy_of_measured_flight_path.mat
new file mode 100644
index 0000000000000000000000000000000000000000..4c152a423216e99ff9e71484fc3a7f391857e77a
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/Copy_of_measured_flight_path.mat differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad.m
new file mode 100644
index 0000000000000000000000000000000000000000..930cb97ef0054a653c05cec97246b19a8c4ffa1f
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad.m
@@ -0,0 +1,126 @@
+function [X_dot] = compute_quad(t, X, U)
+% Dynamic equation for a quadcopter (Bolandil-ICA-2013)
+%         x1  = x
+%         x2  = y
+%         x3  = z
+%         x4  = phi
+%         x5  = theta
+%   X  =  x6  = psi
+%         x7  = x_dot
+%         x8  = y_dot
+%         x9  = z_dot
+%         x10 = phi_dot
+%         x11 = theta_dot
+%         x12 = psi_dot
+%
+%
+%             x1_dot  = x7
+%             x2_dot  = x8
+%             x3_dot  = x9
+%             x4_dot  = x10
+%             x5_dot  = x11
+%   X_dot  =  x6_dot  = x12
+%             x7_dot  = x_ddot     = -(sin(theta)*cos(phi))*(u1/m) 
+%                                  = -(sin(x5)*cos(x4))*(u1/m)
+%
+%             x8_dot  = y_ddot     = sin(phi)*(u1/m)
+%                                  = sin(x4)*(u1/m)
+%
+%             x9_dot  = z_ddot     = -(cos(theta)*cos(phi))*(u1/m) + g
+%                                  = -(cos(x5)*cos(x4))*(u1/m) + g
+%
+%             x10_dot = phi_ddot   =   -psi_dot*theta_dot*cos(phi)
+%                                    + [len*cos(psi)*u2]/I_xx
+%                                    - [len*sin(psi)*u3]/I_yy
+%                                    + [(I_yy - I_zz)/I_xx]*(psi_dot - theta_dot*sin(phi))*(theta_dot*cos(phi))
+%
+%                                  =   -x12*x11*cos(x4)
+%                                    + [len*cos(x6)*u2]/I_xx
+%                                    - [len*sin(x6)*u3]/I_yy
+%                                    + [(I_yy - I_zz)/I_xx]*(x12 - x11*sin(x4))*(x11*cos(x4))
+%
+%             x11_dot = theta_ddot =   (psi_dot*phi_dot)/cos(phi) + phi_dot*theta_dot*tan(phi) 
+%                                    + [len*(sin(psi)/cos(phi))*u2]/I_xx 
+%                                    + [len*(cos(psi)/cos(phi))*u3]/I_yy 
+%                                    - [(I_yy - I_zz)/I_xx]*(psi_dot - theta_dot*sin(phi))*(phi_dot/cos(phi))
+%
+%                                  =   (x12*x10)/cos(x4) + x10*x11*tan(x4)
+%                                    + [len*(sin(x6)/cos(x4))*u2]/I_xx 
+%                                    + [len*(cos(x6)/cos(x4))*u3]/I_yy
+%                                    - [(I_yy - I_zz)/I_xx]*(x12 - x11*sin(x4))*(x10/cos(x4))
+%
+%             x12_dot = psi_ddot   =   phi_dot*psi_dot*tan(phi) + (phi_dot*theta_dot)/cos(phi) 
+%                                    + [len*sin(psi)*tan(phi)*u2]/I_xx
+%                                    + [len*cos(psi)*tan(phi)*u3]/I_yy 
+%                                    + [len*u4]/I_zz 
+%                                    - [(I_yy - I_zz)/I_xx]*(psi_dot - theta_dot*sin(phi))*(phi_dot*tan(phi))
+%
+%                                  =   x10*x12*tan(x4) + (x10*x11)/cos(x4) 
+%                                    + [len*sin(x6)*tan(x4)*u2]/I_xx 
+%                                    + [len*cos(x6)*tan(x4)*u3]/I_yy 
+%                                    + [len*u4]/I_zz 
+%                                    - [(I_yy - I_zz)/I_xx]*(x12 - x11*sin(x4))*(x10*tan(x4))
+%
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+
+  % Constants
+  g = 9.8;        % (m/s^2) Gravity
+  m = 28/1000;    % (Kg) Mass of quad (Crazyflie max take-off weight  ~42g) (Foster-2015)
+  len = (.092/2); % (m) Length of quad lever arm for yaw force (92mm diameter of CrazyFlie)
+  len_xy = (.092/2)*sin(pi/4); % (m) Length of quad lever arm for pitch/roll force: Quad arm length * projection onto pitch/roll axis
+  I_xx = 1.33e-5; % (Kg*m^2) Moment of inertia about X-axis (McInerney-MS-Thesis-2017)
+  I_yy = 1.33e-5; % (Kg*m^2) Moment of inertia about Y-axis (McInerney-MS-Thesis-2017)
+  I_zz = 2.64e-5; % (Kg*m^2) Moment of inertia about Z-axis (McInerney-MS-Thesis-2017)
+
+  % To reduce indexing syntax, reassign input vector
+  % to individule state varibles
+  x1  = X(1);  % x
+  x2  = X(2);  % y
+  x3  = X(3);  % z
+  x4  = X(4);  % phi
+  x5  = X(5);  % theta
+  x6  = X(6);  % psi
+  x7  = X(7);  % x_dot
+  x8  = X(8);  % y_dot
+  x9  = X(9);  % z_dot
+  x10 = X(10); % phi_dot
+  x11 = X(11); % theta_dot
+  x12 = X(12); % psi_dot
+
+  % Input forces
+  u1 = U(1); % Total force (Note: always normal to yaw motion): Crazy Fly max ~.6 N (Foster-2015)
+  u2 = U(2); % Roll force
+  u3 = U(3); % Pitch force
+  u4 = U(4); % Yaw force  
+
+  % Compute Quad dynamics
+  x1_dot  = x7;   % x_dot
+  x2_dot  = x8;   % y_dot
+  x3_dot  = x9;   % z_dot
+  x4_dot  = x10;  % phi_dot
+  x5_dot  = x11;  % theta_dot
+  x6_dot  = x12;  % psi_dot
+  x7_dot  =   -(sin(x5)*cos(x4))*(u1/m);      % x_ddot
+  x8_dot  =   sin(x4)*(u1/m);                 % y_ddot
+  x9_dot  =   -(cos(x5)*cos(x4))*(u1/m) + g;  % z_ddot
+
+  x10_dot =   -x12*x11*cos(x4) ...
+            + (len_xy*cos(x6)*u2)/I_xx ...
+            - (len_xy*sin(x6)*u3)/I_yy ...
+            + ((I_yy - I_zz)/I_xx)*(x12 - x11*sin(x4))*(x11*cos(x4)); % phi_ddot
+
+  x11_dot =   (x12*x10)/cos(x4) + x10*x11*tan(x4) ...
+            + (len_xy*(sin(x6)/cos(x4))*u2)/I_xx ... 
+            + (len_xy*(cos(x6)/cos(x4))*u3)/I_yy ... 
+            - ((I_yy - I_zz)/I_xx)*(x12 - x11*sin(x4))*(x10/cos(x4)); % theta_ddot
+
+  x12_dot =   x10*x12*tan(x4) + (x10*x11)/cos(x4) ... 
+            + (len_xy*sin(x6)*tan(x4)*u2)/I_xx ... 
+            + (len_xy*cos(x6)*tan(x4)*u3)/I_yy ... 
+            + (len*u4)/I_zz ... 
+            - ((I_yy - I_zz)/I_xx)*(x12 - x11*sin(x4))*(x10*tan(x4)); % psi_ddot
+
+  % X_dot : State variable direvative output
+  X_dot = [x1_dot x2_dot x3_dot x4_dot x5_dot x6_dot ... 
+           x7_dot x8_dot x9_dot x10_dot x11_dot x12_dot]';
+end
\ No newline at end of file
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_lqr_k.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_lqr_k.m
new file mode 100644
index 0000000000000000000000000000000000000000..25b1a6683fb003e102e799ea49e6a404519c6982
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_lqr_k.m
@@ -0,0 +1,75 @@
+% File name: compute_quad_lqr_k
+% Author: Phillip Jones (7/26/2022)
+% Description: Compute Quadcopter K for LQR control law for CrazyFlie
+
+%  CrazyFlie constants:
+g = 9.8;        % (m/s^2) Gravity
+m = 23.1/1000;    % (Kg) Mass of quad (Crazyflie max take-off weight  ~42g) (Foster-2015)
+len = (.092/2); % (m) Length of quad lever arm for yaw force (92mm diameter of CrazyFlie)
+len_xy = (.092/2)*sin(pi/4); % (m) Length of quad lever arm for pitch/roll force: Quad arm length * projection onto pitch/roll axis
+I_xx = 1.33e-5; % (Kg*m^2) Moment of inertia about X-axis (McInerney-MS-Thesis-2017)
+I_yy = 1.33e-5; % (Kg*m^2) Moment of inertia about Y-axis (McInerney-MS-Thesis-2017)
+I_zz = 2.64e-5; % (Kg*m^2) Moment of inertia about Z-axis (McInerney-MS-Thesis-2017)
+
+%  Matrix A :
+%     x   y   z   phi theta psi x_dot y_dot z_dot phi_dot theta_dot psi_dot    
+%     x1  x2  x3  x4   x5   x6   x7    x8    x9     x10      x11    x12
+A = [ 0   0   0   0    0    0    1     0     0      0        0      0; ...
+      0   0   0   0    0    0    0     1     0      0        0      0; ...
+      0   0   0   0    0    0    0     0     1      0        0      0; ...
+      0   0   0   0    0    0    0     0     0      1        0      0; ...
+      0   0   0   0    0    0    0     0     0      0        1      0; ...
+      0   0   0   0    0    0    0     0     0      0        0      1; ...
+      0   0   0   0   -g    0    0     0     0      0        0      0; ...
+      0   0   0   g    0    0    0     0     0      0        0      0; ...
+      0   0   0   0    0    0    0     0     0      0        0      0; ...
+      0   0   0   0    0    0    0     0     0      0        0      0; ...
+      0   0   0   0    0    0    0     0     0      0        0      0; ...
+      0   0   0   0    0    0    0     0     0      0        0      0];
+
+%   Matrix B :
+%    Thurst  Phi force Theta force  Psi force
+%     u1       u2        u3         u4
+B = [ 0        0         0          0; ...    % x1_dot  (x_dot) 
+      0        0         0          0; ...    % x2_dot  (y_dot)
+      0        0         0          0; ...    % x3_dot  (z_dot)
+      0        0         0          0; ...    % x4_dot  (phi_dot)
+      0        0         0          0; ...    % x5_dot  (theta_dot)
+      0        0         0          0; ...    % x6_dot  (psi_dot)
+      0        0         0          0; ...    % x7_dot  (x_ddot)
+      0        0         0          0; ...    % x8_dot  (y_ddot)
+     -1/m      0         0          0; ...    % x9_dot  (z_ddot)
+      0   len_xy/I_xx    0          0; ...    % x10_dot (phi_ddot)
+      0        0     -len_xy/I_yy    0; ...    % x11_dot (theta_ddot)
+      0        0         0       len/I_zz ];  % x12_dot (psi_ddot)
+
+
+%  LQR: Q and R matrix (Note the Q and R matrix is differnt from the Q and
+%       R in LQR.
+%
+Q = [ 1  0  0  0   0   0  0  0  0   0  0  0; ...
+      0  1  0  0   0   0  0  0  0   0  0  0; ...
+      0  0  1  0   0   0  0  0  0   0  0  0; ...
+      0  0  0 .0000001 0   0  0  0  0   0  0  0; ...
+      0  0  0  0 .0000001  0  0  0  0   0  0  0; ...
+      0  0  0  0   0   0.0000001  0  0  0   0  0  0; ...
+      0  0  0  0   0   0 2  0  0   0  0  0; ...
+      0  0  0  0   0   0  0 2  0   0  0  0; ...
+      0  0  0  0   0   0  0  0 2  0  0  0; ...
+      0  0  0  0   0   0  0  0  0 .0000001  0  0; ...
+      0  0  0  0   0   0  0  0  0   0 .0000001 0; ...
+      0  0  0  0   0   0  0  0  0   0  0  0.0000001];
+
+R = [1  0    0    0; ...
+     0    1  0    0; ...
+     0    0    1  0; ...
+     0    0    0    10000000];
+
+[K, S, E] = lqr(A,B,Q,R);
+
+K
+
+[dK, S, E] = lqrd(A,B,Q,R,.001);
+
+dK
+
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_wrapper.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_wrapper.m
new file mode 100644
index 0000000000000000000000000000000000000000..ebb73868e77b3f5aff0ad6448edc56ec51196a1e
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_wrapper.m
@@ -0,0 +1,28 @@
+function [y, X, U, tspan] = compute_quad_wrapper(tstep, X, U, X_ref,F_hover, tspan)
+
+% tspan=[0 tstep]; 
+X_init = X(end,:); % Initialize state from where last ode left off
+tspan=[tspan(2) tspan(2)+tstep];  % Advance to next time interval
+
+[~, X] = ode45(@(t,X) compute_quad(t,X,U), tspan, X_init); % Simulate
+
+% Xplot = [Xplot; [t, X]]; % log data for plotting later (this is the main thing that contributes to time
+
+% Compute feedback (i.e. Force inputs (U) in terms of state (X) )
+%Get current state;
+X_c = X(end,:);
+
+% LQR control law
+U = lqr_quad_gains(X_c-X_ref); % LQR controller gains applied to error 
+                             % between current state (X_c), and
+                             % refernce setpoint (X_ref).
+
+U(1) = U(1) + F_hover;  % LQR controlling quad at hoover equilibrium 
+
+
+
+
+euler_angles = [X_c(6) X_c(5) X_c(4)];
+displacement = [X_c(1) X_c(2) X_c(3)];
+
+y = [euler_angles displacement]; 
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_wrapper_pid.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_wrapper_pid.m
new file mode 100644
index 0000000000000000000000000000000000000000..45ff880e8db66beae648190955f4f780b9692d47
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/compute_quad_wrapper_pid.m
@@ -0,0 +1,83 @@
+function [y, X, U, tspan, pid_states, pid_gains] = compute_quad_wrapper_pid(tstep, X, U, X_ref,F_hover, tspan, pid_states, pid_gains)
+
+% tspan=[0 tstep]; 
+X_init = X(end,:); % Initialize state from where last ode left off
+tspan=[tspan(2) tspan(2)+tstep];  % Advance to next time interval
+
+alt_error_sum = pid_states(1);
+alt_error_prev = pid_states(2); 
+y_error_sum = pid_states(3);
+y_error_prev = pid_states(4);
+phi_error_sum = pid_states(5);
+phi_error_prev = pid_states(6);
+x_error_sum = pid_states(7);
+x_error_prev = pid_states(8);
+theta_error_sum = pid_states(9);
+theta_error_prev = pid_states(10);
+phi_setpoint = pid_states(11);
+theta_setpoint = pid_states(12);
+
+Kp_alt = pid_gains(1); 
+Ki_alt = pid_gains(2); 
+Kd_alt  = pid_gains(3);
+Kp_y  = pid_gains(4);
+Ki_y  = pid_gains(5);
+Kd_y = pid_gains(6);
+Kp_phi  = pid_gains(7);
+Ki_phi  = pid_gains(8);
+Kd_phi  = pid_gains(9);
+Kp_x  = pid_gains(10);
+Ki_x  = pid_gains(11);
+Kd_x = pid_gains(12);
+Kp_theta  = pid_gains(13);
+Ki_theta = pid_gains(14);
+Kd_theta = pid_gains(15);
+
+[~, X] = ode45(@(t,X) compute_quad(t,X,U), tspan, X_init); % Simulate
+
+U = [0 0 0 0];
+% Xplot = [Xplot; [t, X]]; % log data for plotting later (this is the main thing that contributes to time
+
+% Compute feedback (i.e. Force inputs (U) in terms of state (X) )
+%Get current state;
+X_c = X(end,:);
+
+  % Altitude PID control
+alt_c = -X_c(3); % Current Altitude is -Z, as Z-axis points down
+
+[alt_cmd, alt_error_sum, alt_error_prev] = pid_ctrl(X_ref(3),alt_c, ...
+    Kp_alt, Ki_alt, Kd_alt, alt_error_sum, alt_error_prev);
+U(1) = alt_cmd;
+
+
+  % Y position (controlled by phi angle)
+y_c = X_c(2); % Current Y position
+[y_cmd, y_error_sum, y_error_prev] = pid_ctrl(X_ref(2),y_c, ...
+    Kp_y, Ki_y, Kd_y, y_error_sum, y_error_prev);
+phi_setpoint = y_cmd; % Use Y correction command to drive phi setpoint
+
+  % Roll (phi) angle
+phi_c = X_c(4); % Current angle phi
+[phi_cmd, phi_error_sum, phi_error_prev] = pid_ctrl(phi_setpoint,phi_c, ...
+    Kp_phi, Ki_phi, Kd_phi, phi_error_sum, phi_error_prev);
+U(2) = phi_cmd; %phi rotation (roll), impacts Y-position @ Yaw = 0
+
+  % X position (controlled by theta angle)
+x_c = X_c(1); % Current X position
+[x_cmd, x_error_sum, x_error_prev] = pid_ctrl(X_ref(1),x_c, ...
+    Kp_x, Ki_x, Kd_x, x_error_sum, x_error_prev);
+theta_setpoint = -x_cmd; % Use X correction command to drive -theta setpoint
+
+  % Pitch (theta) angle
+theta_c = X_c(5); % Current angle theta
+[theta_cmd, theta_error_sum, theta_error_prev] = pid_ctrl(theta_setpoint,theta_c, ...
+    Kp_theta, Ki_theta, Kd_theta, theta_error_sum, theta_error_prev);
+U(3) = theta_cmd; %theta rotation (pitch), impacts X-position @ Yaw = 0
+
+pid_states = [alt_error_sum alt_error_prev y_error_sum y_error_prev phi_error_sum phi_error_prev x_error_sum x_error_prev theta_error_sum theta_error_prev phi_setpoint theta_setpoint];
+pid_gains = [Kp_alt Ki_alt Kd_alt Kp_y Ki_y Kd_y Kp_phi Ki_phi Kd_phi Kp_x Ki_x Kd_x Kp_theta Ki_theta Kd_theta];
+
+euler_angles = [X_c(6) X_c(5) X_c(4)];
+displacement = [X_c(1) X_c(2) X_c(3)];
+
+y = [euler_angles displacement]; 
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slx b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slx
new file mode 100644
index 0000000000000000000000000000000000000000..3f9141f63ee76c2f1d8a591f0f6cbe552c440047
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slx differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slx.original b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slx.original
new file mode 100644
index 0000000000000000000000000000000000000000..56f241ef5f5c1e8fe9d23434ae62aa611cb456da
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slx.original differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slxc b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slxc
new file mode 100644
index 0000000000000000000000000000000000000000..47e5d26c17f4e7ce4f784010b216817a31b5d45f
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/gamepad_input.slxc differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initialization.mat b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initialization.mat
new file mode 100644
index 0000000000000000000000000000000000000000..6529d85b7f245170fb898bae89596ea60a2a4408
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initialization.mat differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initialization.mldatx b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initialization.mldatx
new file mode 100644
index 0000000000000000000000000000000000000000..9908de55bb08b07464053d99baf4b9ee8a460940
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initialization.mldatx differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initializationFHover.mat b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initializationFHover.mat
new file mode 100644
index 0000000000000000000000000000000000000000..1c1e13bda4fc4245557badb2e0355b22b1ec8b47
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/initializationFHover.mat differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_data.mat b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_data.mat
new file mode 100644
index 0000000000000000000000000000000000000000..7576a63a26066f99c9340f8bff6ca3c68354c0a7
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_data.mat differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..00d6690f889f524cb18a5abede2c34763784788a
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl
@@ -0,0 +1,1029 @@
+#VRML V2.0 utf8
+# Created with V-Realm Builder v2.0
+# Integrated Data Systems Inc.
+# www.ids-net.com
+
+PointLight {
+  location -0.8 1 1
+}
+PointLight {
+  location 1.1 1.1 0
+}
+DEF Viewport_heli Viewpoint {
+  position 0.024 -0.191 11.9975
+  orientation 1 0 0 0.188496
+}
+DEF Helicopter Transform {
+  scale 0.108 0.108 0.108
+  children [
+    DEF Rotor_1 Transform {
+      translation 10 0 10
+      scale 1.00001 1.00001 1.00001
+      children Shape {
+        appearance Appearance {
+          material Material {
+            specularColor 0.3 0.3 0.3
+            shininess 0.3
+            diffuseColor 0.6163 0.6163 0.6163
+            ambientIntensity 0.9551
+          }
+        }
+        geometry IndexedFaceSet {
+          creaseAngle 1
+          coordIndex [
+            78, 171, 172, 63, -1, 
+            74, 163, 164, 67, -1, 
+            62, 175, 63, 172, 64, 170, 193, 65, 168, 66, 166, 67, 164, 68, 162, 69, 70, 173, -1, 
+            165, 74, 67, 166, -1, 
+            173, 70, 71, 174, -1, 
+            175, 62, 79, 176, -1, 
+            167, 75, 66, 168, -1, 
+            175, 176, 78, 63, -1, 
+            73, 161, 162, 68, -1, 
+            77, 169, 170, 64, -1, 
+            62, 173, 174, 79, -1, 
+            75, 165, 166, 66, -1, 
+            174, 71, 72, 161, 73, 163, 74, 165, 75, 167, 76, 192, 169, 77, 171, 78, 176, 79, -1, 
+            163, 73, 68, 164, -1, 
+            171, 77, 64, 172, -1, 
+            192, 76, 65, 193, -1, 
+            169, 192, 193, 170, -1, 
+            161, 72, 69, 162, -1, 
+            72, 71, 70, 69, -1, 
+            76, 167, 168, 65, -1, 
+            -1 
+          ]
+          coord DEF _v2%0 Coordinate {
+            point [
+              1.87355 -2.12 -0.139033,
+              0.783522 -2.076 0.446909,
+              0.783515 -2.267 0.566909,
+              0.783572 -2.266 -0.517091,
+              1.87352 -2.12 0.566967,
+              1.80752 -2.12 0.566963,
+              1.87359 -2.266 -0.877033,
+              1.87355 -2.267 -0.047033,
+              1.87352 -2.267 0.566967,
+              1.80752 -2.267 0.566963,
+              1.80755 -2.12 -0.129037,
+              1.80755 -2.267 -0.037037,
+              1.80759 -2.266 -0.867037,
+              1.80659 -2.12 -0.874037,
+              1.87259 -2.12 -0.884034,
+              -1.18645 -2.12 -0.139194,
+              -1.18541 -2.12 -0.884194,
+              -1.11941 -2.12 -0.874191,
+              -1.12041 -2.266 -0.867191,
+              -1.12045 -2.12 -0.129191,
+              -1.12048 -2.12 0.566809,
+              -1.12048 -2.267 0.566809,
+              -1.18649 -2.267 0.566806,
+              -1.18645 -2.267 -0.047194,
+              -1.12045 -2.267 -0.037191,
+              -1.18641 -2.266 -0.877194,
+              -1.18649 -2.12 0.566806,
+              -0.096428 -2.266 -0.517137,
+              -0.096485 -2.267 0.566863,
+              -0.096479 -2.076 0.446863,
+              0.591406 -3.166 2.6379,
+              0.095406 -3.166 2.63787,
+              0.095406 -2.912 2.63787,
+              0.219395 -3.166 2.85388,
+              0.219395 -2.912 2.85388,
+              0.467395 -2.912 2.85389,
+              0.467395 -3.166 2.85389,
+              0.467418 -2.912 2.42289,
+              0.219418 -2.912 2.42288,
+              0.591406 -2.912 2.6379,
+              0.219418 -3.166 2.42288,
+              0.467418 -3.166 2.42289,
+              0.434395 -3.132 2.85389,
+              0.252395 -3.132 2.85388,
+              0.252395 -2.946 2.85388,
+              0.434395 -2.946 2.85389,
+              0.269336 -3.076 3.96788,
+              0.417336 -3.129 3.96789,
+              0.417336 -3.076 3.96789,
+              0.269336 -3.129 3.96788,
+              0.269395 -3.012 2.85388,
+              0.269395 -3.066 2.85388,
+              0.367395 -2.962 2.85389,
+              0.319395 -2.962 2.85388,
+              0.417395 -3.066 2.85389,
+              0.417395 -3.012 2.85389,
+              0.367336 -3.179 3.96789,
+              0.319336 -3.179 3.96789,
+              0.319395 -3.116 2.85388,
+              0.367395 -3.116 2.85389,
+              0.319336 -3.026 3.96789,
+              0.367336 -3.026 3.96789,
+              6.61556 0.193 -0.215784,
+              5.14735 -0.086 3.80614,
+              1.43223 -0.234 5.94594,
+              -4.46066 -0.086 3.80563,
+              -5.92844 0.192 -0.216444,
+              -4.46123 0.471 -4.23737,
+              -0.74512 0.619 -6.37717,
+              3.47884 0.568 -5.63495,
+              5.14777 0.471 -4.23786,
+              5.14777 0.532 -4.23786,
+              3.47884 0.628 -5.63495,
+              -0.74512 0.68 -6.37717,
+              -4.46123 0.531 -4.23737,
+              -5.92844 0.253 -0.216444,
+              -4.46066 -0.025 3.80563,
+              1.43223 -0.173 5.94594,
+              5.14735 -0.025 3.80614,
+              6.61556 0.253 -0.215784,
+              0.614972 0.679 -8.1101,
+              0.614936 0.106 -7.4281,
+              0.614936 -1.196 -7.4281,
+              0.614972 -1.767 -8.1101,
+              0.615018 -1.768 -9.0011,
+              0.615054 -1.196 -9.6831,
+              0.615062 -0.319 -9.8381,
+              0.615054 0.106 -9.6831,
+              0.615039 0.453 -9.3931,
+              0.615018 0.679 -9.0011,
+              0.530019 0.679 -9.0011,
+              0.530039 0.453 -9.39311,
+              0.530054 0.106 -9.68311,
+              0.530062 -0.319 -9.83811,
+              0.530054 -1.196 -9.68311,
+              0.530019 -1.768 -9.0011,
+              0.529972 -1.767 -8.1101,
+              0.529936 -1.196 -7.4281,
+              0.529928 -0.319 -7.2731,
+              0.529936 0.106 -7.4281,
+              0.529972 0.679 -8.1101,
+              0.255231 -2.14915 -7.3791,
+              0.758162 -2.59984 3.36791,
+              0.594847 -2.54881 3.72511,
+              -0.062854 -2.59984 3.36787,
+              0.594839 -1.93645 3.87253,
+              0.100415 -1.93645 3.8725,
+              0.75818 -1.70965 3.02771,
+              -0.062836 -1.70965 3.02767,
+              0.758223 -1.02925 2.19989,
+              -0.062793 -1.02925 2.19985,
+              0.758299 -0.830803 0.75404,
+              -0.062717 -0.830803 0.753997,
+              0.758301 -0.314833 0.72002,
+              -0.062715 -0.314833 0.719977,
+              0.758416 -0.415926 -1.4647,
+              -0.0626 -0.415926 -1.46475,
+              -0.062585 -0.937566 -1.74258,
+              0.477454 -1.87132 -6.6023,
+              0.214366 -1.87132 -6.60231,
+              0.441263 -0.495408 -8.43416,
+              0.250751 -0.495408 -8.43417,
+              0.414074 -0.461388 -8.95013,
+              0.277994 -0.461388 -8.95014,
+              0.436671 -2.14915 -7.37909,
+              0.4548 -2.34193 -7.08992,
+              0.241608 -2.34193 -7.08993,
+              0.758426 -3.16939 -1.65658,
+              -0.06259 -3.16939 -1.65662,
+              0.758217 -3.03428 2.31419,
+              -0.062799 -3.03428 2.31415,
+              -0.062716 -1.54522 0.742657,
+              -0.062569 -1.57261 -2.04875,
+              0.7583 -1.54522 0.7427,
+              0.758431 -0.937566 -1.74253,
+              0.758447 -1.57261 -2.04871,
+              0.100423 -2.54881 3.72509,
+              -0.476109 -1.54522 0.742637,
+              -0.47611 -0.830803 0.753977,
+              -0.063333 -1.54522 0.742658,
+              -0.063334 -0.830803 0.753998,
+              -0.475978 -0.937566 -1.74259,
+              -0.063202 -0.937566 -1.74257,
+              1.17046 -0.830803 0.754063,
+              0.757682 -0.830803 0.754041,
+              1.17064 -1.59392 -2.71303,
+              1.17046 -1.54522 0.742723,
+              0.757683 -1.54522 0.742701,
+              0.75783 -1.57261 -2.04871,
+              1.17059 -0.937566 -1.74251,
+              -0.475928 -1.57816 -2.70774,
+              -0.475962 -1.57261 -2.04878,
+              -0.063153 -0.955725 -2.674,
+              -0.475929 -0.955725 -2.67402,
+              -0.063186 -1.57261 -2.04875,
+              -0.063152 -1.57816 -2.70772,
+              1.17061 -1.57261 -2.04869,
+              1.17064 -0.971488 -2.67932,
+              0.757865 -1.59392 -2.71305,
+              0.757814 -0.937566 -1.74253,
+              0.757863 -0.971488 -2.67934,
+              1.43188 0.68 -6.37806,
+              1.43188 0.619 -6.37806,
+              -2.79216 0.628 -5.63428,
+              -2.79216 0.567 -5.63428,
+              -5.55033 0.401 -2.35642,
+              -5.55033 0.34 -2.35642,
+              -5.54956 0.105 1.92358,
+              -5.54956 0.044 1.92358,
+              -0.744768 -0.173 5.94583,
+              -0.744768 -0.234 5.94583,
+              3.47927 -0.122 5.20305,
+              3.47927 -0.183 5.20305,
+              6.23667 0.341 -2.3568,
+              6.23667 0.402 -2.3568,
+              6.23644 0.044 1.9242,
+              6.23644 0.105 1.9242,
+              0.530062 -0.771 -9.83811,
+              0.615062 -0.771 -9.8381,
+              0.530039 -1.542 -9.3921,
+              0.615039 -1.542 -9.3921,
+              0.529995 -1.846 -8.5551,
+              0.614995 -1.846 -8.5551,
+              0.529951 -1.542 -7.7181,
+              0.614951 -1.542 -7.7181,
+              0.529928 -0.771 -7.2731,
+              0.614928 -0.771 -7.2731,
+              0.614928 -0.319 -7.2731,
+              0.529951 0.453 -7.7181,
+              0.614951 0.453 -7.7181,
+              0.614995 0.757 -8.5551,
+              0.529995 0.757 -8.5551,
+              -2.79173 -0.122 5.20272,
+              -2.79173 -0.183 5.20272 
+            ]
+          }
+        }
+      }
+    }
+    DEF Rotor_2 Transform {
+      translation 10 0 -10
+      scale 0.999617 0.999617 0.999617
+      children Shape {
+        appearance Appearance {
+          material Material {
+            specularColor 0.3 0.3 0.3
+            shininess 0.3
+            diffuseColor 0.6163 0.6163 0.6163
+            ambientIntensity 0.9551
+          }
+        }
+        geometry IndexedFaceSet {
+          creaseAngle 1
+          coordIndex [
+            78, 171, 172, 63, -1, 
+            74, 163, 164, 67, -1, 
+            62, 175, 63, 172, 64, 170, 193, 65, 168, 66, 166, 67, 164, 68, 162, 69, 70, 173, -1, 
+            165, 74, 67, 166, -1, 
+            173, 70, 71, 174, -1, 
+            175, 62, 79, 176, -1, 
+            167, 75, 66, 168, -1, 
+            175, 176, 78, 63, -1, 
+            73, 161, 162, 68, -1, 
+            77, 169, 170, 64, -1, 
+            62, 173, 174, 79, -1, 
+            75, 165, 166, 66, -1, 
+            174, 71, 72, 161, 73, 163, 74, 165, 75, 167, 76, 192, 169, 77, 171, 78, 176, 79, -1, 
+            163, 73, 68, 164, -1, 
+            171, 77, 64, 172, -1, 
+            192, 76, 65, 193, -1, 
+            169, 192, 193, 170, -1, 
+            161, 72, 69, 162, -1, 
+            72, 71, 70, 69, -1, 
+            76, 167, 168, 65, -1, 
+            -1 
+          ]
+          coord Coordinate {
+            point [
+              1.87355 -2.12 -0.139033,
+              0.783522 -2.076 0.446909,
+              0.783515 -2.267 0.566909,
+              0.783572 -2.266 -0.517091,
+              1.87352 -2.12 0.566967,
+              1.80752 -2.12 0.566963,
+              1.87359 -2.266 -0.877033,
+              1.87355 -2.267 -0.047033,
+              1.87352 -2.267 0.566967,
+              1.80752 -2.267 0.566963,
+              1.80755 -2.12 -0.129037,
+              1.80755 -2.267 -0.037037,
+              1.80759 -2.266 -0.867037,
+              1.80659 -2.12 -0.874037,
+              1.87259 -2.12 -0.884034,
+              -1.18645 -2.12 -0.139194,
+              -1.18541 -2.12 -0.884194,
+              -1.11941 -2.12 -0.874191,
+              -1.12041 -2.266 -0.867191,
+              -1.12045 -2.12 -0.129191,
+              -1.12048 -2.12 0.566809,
+              -1.12048 -2.267 0.566809,
+              -1.18649 -2.267 0.566806,
+              -1.18645 -2.267 -0.047194,
+              -1.12045 -2.267 -0.037191,
+              -1.18641 -2.266 -0.877194,
+              -1.18649 -2.12 0.566806,
+              -0.096428 -2.266 -0.517137,
+              -0.096485 -2.267 0.566863,
+              -0.096479 -2.076 0.446863,
+              0.591406 -3.166 2.6379,
+              0.095406 -3.166 2.63787,
+              0.095406 -2.912 2.63787,
+              0.219395 -3.166 2.85388,
+              0.219395 -2.912 2.85388,
+              0.467395 -2.912 2.85389,
+              0.467395 -3.166 2.85389,
+              0.467418 -2.912 2.42289,
+              0.219418 -2.912 2.42288,
+              0.591406 -2.912 2.6379,
+              0.219418 -3.166 2.42288,
+              0.467418 -3.166 2.42289,
+              0.434395 -3.132 2.85389,
+              0.252395 -3.132 2.85388,
+              0.252395 -2.946 2.85388,
+              0.434395 -2.946 2.85389,
+              0.269336 -3.076 3.96788,
+              0.417336 -3.129 3.96789,
+              0.417336 -3.076 3.96789,
+              0.269336 -3.129 3.96788,
+              0.269395 -3.012 2.85388,
+              0.269395 -3.066 2.85388,
+              0.367395 -2.962 2.85389,
+              0.319395 -2.962 2.85388,
+              0.417395 -3.066 2.85389,
+              0.417395 -3.012 2.85389,
+              0.367336 -3.179 3.96789,
+              0.319336 -3.179 3.96789,
+              0.319395 -3.116 2.85388,
+              0.367395 -3.116 2.85389,
+              0.319336 -3.026 3.96789,
+              0.367336 -3.026 3.96789,
+              6.61556 0.193 -0.215784,
+              5.14735 -0.086 3.80614,
+              1.43223 -0.234 5.94594,
+              -4.46066 -0.086 3.80563,
+              -5.92844 0.192 -0.216444,
+              -4.46123 0.471 -4.23737,
+              -0.74512 0.619 -6.37717,
+              3.47884 0.568 -5.63495,
+              5.14777 0.471 -4.23786,
+              5.14777 0.532 -4.23786,
+              3.47884 0.628 -5.63495,
+              -0.74512 0.68 -6.37717,
+              -4.46123 0.531 -4.23737,
+              -5.92844 0.253 -0.216444,
+              -4.46066 -0.025 3.80563,
+              1.43223 -0.173 5.94594,
+              5.14735 -0.025 3.80614,
+              6.61556 0.253 -0.215784,
+              0.614972 0.679 -8.1101,
+              0.614936 0.106 -7.4281,
+              0.614936 -1.196 -7.4281,
+              0.614972 -1.767 -8.1101,
+              0.615018 -1.768 -9.0011,
+              0.615054 -1.196 -9.6831,
+              0.615062 -0.319 -9.8381,
+              0.615054 0.106 -9.6831,
+              0.615039 0.453 -9.3931,
+              0.615018 0.679 -9.0011,
+              0.530019 0.679 -9.0011,
+              0.530039 0.453 -9.39311,
+              0.530054 0.106 -9.68311,
+              0.530062 -0.319 -9.83811,
+              0.530054 -1.196 -9.68311,
+              0.530019 -1.768 -9.0011,
+              0.529972 -1.767 -8.1101,
+              0.529936 -1.196 -7.4281,
+              0.529928 -0.319 -7.2731,
+              0.529936 0.106 -7.4281,
+              0.529972 0.679 -8.1101,
+              0.255231 -2.14915 -7.3791,
+              0.758162 -2.59984 3.36791,
+              0.594847 -2.54881 3.72511,
+              -0.062854 -2.59984 3.36787,
+              0.594839 -1.93645 3.87253,
+              0.100415 -1.93645 3.8725,
+              0.75818 -1.70965 3.02771,
+              -0.062836 -1.70965 3.02767,
+              0.758223 -1.02925 2.19989,
+              -0.062793 -1.02925 2.19985,
+              0.758299 -0.830803 0.75404,
+              -0.062717 -0.830803 0.753997,
+              0.758301 -0.314833 0.72002,
+              -0.062715 -0.314833 0.719977,
+              0.758416 -0.415926 -1.4647,
+              -0.0626 -0.415926 -1.46475,
+              -0.062585 -0.937566 -1.74258,
+              0.477454 -1.87132 -6.6023,
+              0.214366 -1.87132 -6.60231,
+              0.441263 -0.495408 -8.43416,
+              0.250751 -0.495408 -8.43417,
+              0.414074 -0.461388 -8.95013,
+              0.277994 -0.461388 -8.95014,
+              0.436671 -2.14915 -7.37909,
+              0.4548 -2.34193 -7.08992,
+              0.241608 -2.34193 -7.08993,
+              0.758426 -3.16939 -1.65658,
+              -0.06259 -3.16939 -1.65662,
+              0.758217 -3.03428 2.31419,
+              -0.062799 -3.03428 2.31415,
+              -0.062716 -1.54522 0.742657,
+              -0.062569 -1.57261 -2.04875,
+              0.7583 -1.54522 0.7427,
+              0.758431 -0.937566 -1.74253,
+              0.758447 -1.57261 -2.04871,
+              0.100423 -2.54881 3.72509,
+              -0.476109 -1.54522 0.742637,
+              -0.47611 -0.830803 0.753977,
+              -0.063333 -1.54522 0.742658,
+              -0.063334 -0.830803 0.753998,
+              -0.475978 -0.937566 -1.74259,
+              -0.063202 -0.937566 -1.74257,
+              1.17046 -0.830803 0.754063,
+              0.757682 -0.830803 0.754041,
+              1.17064 -1.59392 -2.71303,
+              1.17046 -1.54522 0.742723,
+              0.757683 -1.54522 0.742701,
+              0.75783 -1.57261 -2.04871,
+              1.17059 -0.937566 -1.74251,
+              -0.475928 -1.57816 -2.70774,
+              -0.475962 -1.57261 -2.04878,
+              -0.063153 -0.955725 -2.674,
+              -0.475929 -0.955725 -2.67402,
+              -0.063186 -1.57261 -2.04875,
+              -0.063152 -1.57816 -2.70772,
+              1.17061 -1.57261 -2.04869,
+              1.17064 -0.971488 -2.67932,
+              0.757865 -1.59392 -2.71305,
+              0.757814 -0.937566 -1.74253,
+              0.757863 -0.971488 -2.67934,
+              1.43188 0.68 -6.37806,
+              1.43188 0.619 -6.37806,
+              -2.79216 0.628 -5.63428,
+              -2.79216 0.567 -5.63428,
+              -5.55033 0.401 -2.35642,
+              -5.55033 0.34 -2.35642,
+              -5.54956 0.105 1.92358,
+              -5.54956 0.044 1.92358,
+              -0.744768 -0.173 5.94583,
+              -0.744768 -0.234 5.94583,
+              3.47927 -0.122 5.20305,
+              3.47927 -0.183 5.20305,
+              6.23667 0.341 -2.3568,
+              6.23667 0.402 -2.3568,
+              6.23644 0.044 1.9242,
+              6.23644 0.105 1.9242,
+              0.530062 -0.771 -9.83811,
+              0.615062 -0.771 -9.8381,
+              0.530039 -1.542 -9.3921,
+              0.615039 -1.542 -9.3921,
+              0.529995 -1.846 -8.5551,
+              0.614995 -1.846 -8.5551,
+              0.529951 -1.542 -7.7181,
+              0.614951 -1.542 -7.7181,
+              0.529928 -0.771 -7.2731,
+              0.614928 -0.771 -7.2731,
+              0.614928 -0.319 -7.2731,
+              0.529951 0.453 -7.7181,
+              0.614951 0.453 -7.7181,
+              0.614995 0.757 -8.5551,
+              0.529995 0.757 -8.5551,
+              -2.79173 -0.122 5.20272,
+              -2.79173 -0.183 5.20272 
+            ]
+          }
+        }
+      }
+    }
+    DEF Rotor_3 Transform {
+      translation -10 0 -10
+      scale 0.999617 0.999617 0.999617
+      children Shape {
+        appearance Appearance {
+          material Material {
+            specularColor 0.3 0.3 0.3
+            shininess 0.3
+            diffuseColor 0.6163 0.6163 0.6163
+            ambientIntensity 0.9551
+          }
+        }
+        geometry IndexedFaceSet {
+          creaseAngle 1
+          coordIndex [
+            78, 171, 172, 63, -1, 
+            74, 163, 164, 67, -1, 
+            62, 175, 63, 172, 64, 170, 193, 65, 168, 66, 166, 67, 164, 68, 162, 69, 70, 173, -1, 
+            165, 74, 67, 166, -1, 
+            173, 70, 71, 174, -1, 
+            175, 62, 79, 176, -1, 
+            167, 75, 66, 168, -1, 
+            175, 176, 78, 63, -1, 
+            73, 161, 162, 68, -1, 
+            77, 169, 170, 64, -1, 
+            62, 173, 174, 79, -1, 
+            75, 165, 166, 66, -1, 
+            174, 71, 72, 161, 73, 163, 74, 165, 75, 167, 76, 192, 169, 77, 171, 78, 176, 79, -1, 
+            163, 73, 68, 164, -1, 
+            171, 77, 64, 172, -1, 
+            192, 76, 65, 193, -1, 
+            169, 192, 193, 170, -1, 
+            161, 72, 69, 162, -1, 
+            72, 71, 70, 69, -1, 
+            76, 167, 168, 65, -1, 
+            -1 
+          ]
+          coord Coordinate {
+            point [
+              1.87355 -2.12 -0.139033,
+              0.783522 -2.076 0.446909,
+              0.783515 -2.267 0.566909,
+              0.783572 -2.266 -0.517091,
+              1.87352 -2.12 0.566967,
+              1.80752 -2.12 0.566963,
+              1.87359 -2.266 -0.877033,
+              1.87355 -2.267 -0.047033,
+              1.87352 -2.267 0.566967,
+              1.80752 -2.267 0.566963,
+              1.80755 -2.12 -0.129037,
+              1.80755 -2.267 -0.037037,
+              1.80759 -2.266 -0.867037,
+              1.80659 -2.12 -0.874037,
+              1.87259 -2.12 -0.884034,
+              -1.18645 -2.12 -0.139194,
+              -1.18541 -2.12 -0.884194,
+              -1.11941 -2.12 -0.874191,
+              -1.12041 -2.266 -0.867191,
+              -1.12045 -2.12 -0.129191,
+              -1.12048 -2.12 0.566809,
+              -1.12048 -2.267 0.566809,
+              -1.18649 -2.267 0.566806,
+              -1.18645 -2.267 -0.047194,
+              -1.12045 -2.267 -0.037191,
+              -1.18641 -2.266 -0.877194,
+              -1.18649 -2.12 0.566806,
+              -0.096428 -2.266 -0.517137,
+              -0.096485 -2.267 0.566863,
+              -0.096479 -2.076 0.446863,
+              0.591406 -3.166 2.6379,
+              0.095406 -3.166 2.63787,
+              0.095406 -2.912 2.63787,
+              0.219395 -3.166 2.85388,
+              0.219395 -2.912 2.85388,
+              0.467395 -2.912 2.85389,
+              0.467395 -3.166 2.85389,
+              0.467418 -2.912 2.42289,
+              0.219418 -2.912 2.42288,
+              0.591406 -2.912 2.6379,
+              0.219418 -3.166 2.42288,
+              0.467418 -3.166 2.42289,
+              0.434395 -3.132 2.85389,
+              0.252395 -3.132 2.85388,
+              0.252395 -2.946 2.85388,
+              0.434395 -2.946 2.85389,
+              0.269336 -3.076 3.96788,
+              0.417336 -3.129 3.96789,
+              0.417336 -3.076 3.96789,
+              0.269336 -3.129 3.96788,
+              0.269395 -3.012 2.85388,
+              0.269395 -3.066 2.85388,
+              0.367395 -2.962 2.85389,
+              0.319395 -2.962 2.85388,
+              0.417395 -3.066 2.85389,
+              0.417395 -3.012 2.85389,
+              0.367336 -3.179 3.96789,
+              0.319336 -3.179 3.96789,
+              0.319395 -3.116 2.85388,
+              0.367395 -3.116 2.85389,
+              0.319336 -3.026 3.96789,
+              0.367336 -3.026 3.96789,
+              6.61556 0.193 -0.215784,
+              5.14735 -0.086 3.80614,
+              1.43223 -0.234 5.94594,
+              -4.46066 -0.086 3.80563,
+              -5.92844 0.192 -0.216444,
+              -4.46123 0.471 -4.23737,
+              -0.74512 0.619 -6.37717,
+              3.47884 0.568 -5.63495,
+              5.14777 0.471 -4.23786,
+              5.14777 0.532 -4.23786,
+              3.47884 0.628 -5.63495,
+              -0.74512 0.68 -6.37717,
+              -4.46123 0.531 -4.23737,
+              -5.92844 0.253 -0.216444,
+              -4.46066 -0.025 3.80563,
+              1.43223 -0.173 5.94594,
+              5.14735 -0.025 3.80614,
+              6.61556 0.253 -0.215784,
+              0.614972 0.679 -8.1101,
+              0.614936 0.106 -7.4281,
+              0.614936 -1.196 -7.4281,
+              0.614972 -1.767 -8.1101,
+              0.615018 -1.768 -9.0011,
+              0.615054 -1.196 -9.6831,
+              0.615062 -0.319 -9.8381,
+              0.615054 0.106 -9.6831,
+              0.615039 0.453 -9.3931,
+              0.615018 0.679 -9.0011,
+              0.530019 0.679 -9.0011,
+              0.530039 0.453 -9.39311,
+              0.530054 0.106 -9.68311,
+              0.530062 -0.319 -9.83811,
+              0.530054 -1.196 -9.68311,
+              0.530019 -1.768 -9.0011,
+              0.529972 -1.767 -8.1101,
+              0.529936 -1.196 -7.4281,
+              0.529928 -0.319 -7.2731,
+              0.529936 0.106 -7.4281,
+              0.529972 0.679 -8.1101,
+              0.255231 -2.14915 -7.3791,
+              0.758162 -2.59984 3.36791,
+              0.594847 -2.54881 3.72511,
+              -0.062854 -2.59984 3.36787,
+              0.594839 -1.93645 3.87253,
+              0.100415 -1.93645 3.8725,
+              0.75818 -1.70965 3.02771,
+              -0.062836 -1.70965 3.02767,
+              0.758223 -1.02925 2.19989,
+              -0.062793 -1.02925 2.19985,
+              0.758299 -0.830803 0.75404,
+              -0.062717 -0.830803 0.753997,
+              0.758301 -0.314833 0.72002,
+              -0.062715 -0.314833 0.719977,
+              0.758416 -0.415926 -1.4647,
+              -0.0626 -0.415926 -1.46475,
+              -0.062585 -0.937566 -1.74258,
+              0.477454 -1.87132 -6.6023,
+              0.214366 -1.87132 -6.60231,
+              0.441263 -0.495408 -8.43416,
+              0.250751 -0.495408 -8.43417,
+              0.414074 -0.461388 -8.95013,
+              0.277994 -0.461388 -8.95014,
+              0.436671 -2.14915 -7.37909,
+              0.4548 -2.34193 -7.08992,
+              0.241608 -2.34193 -7.08993,
+              0.758426 -3.16939 -1.65658,
+              -0.06259 -3.16939 -1.65662,
+              0.758217 -3.03428 2.31419,
+              -0.062799 -3.03428 2.31415,
+              -0.062716 -1.54522 0.742657,
+              -0.062569 -1.57261 -2.04875,
+              0.7583 -1.54522 0.7427,
+              0.758431 -0.937566 -1.74253,
+              0.758447 -1.57261 -2.04871,
+              0.100423 -2.54881 3.72509,
+              -0.476109 -1.54522 0.742637,
+              -0.47611 -0.830803 0.753977,
+              -0.063333 -1.54522 0.742658,
+              -0.063334 -0.830803 0.753998,
+              -0.475978 -0.937566 -1.74259,
+              -0.063202 -0.937566 -1.74257,
+              1.17046 -0.830803 0.754063,
+              0.757682 -0.830803 0.754041,
+              1.17064 -1.59392 -2.71303,
+              1.17046 -1.54522 0.742723,
+              0.757683 -1.54522 0.742701,
+              0.75783 -1.57261 -2.04871,
+              1.17059 -0.937566 -1.74251,
+              -0.475928 -1.57816 -2.70774,
+              -0.475962 -1.57261 -2.04878,
+              -0.063153 -0.955725 -2.674,
+              -0.475929 -0.955725 -2.67402,
+              -0.063186 -1.57261 -2.04875,
+              -0.063152 -1.57816 -2.70772,
+              1.17061 -1.57261 -2.04869,
+              1.17064 -0.971488 -2.67932,
+              0.757865 -1.59392 -2.71305,
+              0.757814 -0.937566 -1.74253,
+              0.757863 -0.971488 -2.67934,
+              1.43188 0.68 -6.37806,
+              1.43188 0.619 -6.37806,
+              -2.79216 0.628 -5.63428,
+              -2.79216 0.567 -5.63428,
+              -5.55033 0.401 -2.35642,
+              -5.55033 0.34 -2.35642,
+              -5.54956 0.105 1.92358,
+              -5.54956 0.044 1.92358,
+              -0.744768 -0.173 5.94583,
+              -0.744768 -0.234 5.94583,
+              3.47927 -0.122 5.20305,
+              3.47927 -0.183 5.20305,
+              6.23667 0.341 -2.3568,
+              6.23667 0.402 -2.3568,
+              6.23644 0.044 1.9242,
+              6.23644 0.105 1.9242,
+              0.530062 -0.771 -9.83811,
+              0.615062 -0.771 -9.8381,
+              0.530039 -1.542 -9.3921,
+              0.615039 -1.542 -9.3921,
+              0.529995 -1.846 -8.5551,
+              0.614995 -1.846 -8.5551,
+              0.529951 -1.542 -7.7181,
+              0.614951 -1.542 -7.7181,
+              0.529928 -0.771 -7.2731,
+              0.614928 -0.771 -7.2731,
+              0.614928 -0.319 -7.2731,
+              0.529951 0.453 -7.7181,
+              0.614951 0.453 -7.7181,
+              0.614995 0.757 -8.5551,
+              0.529995 0.757 -8.5551,
+              -2.79173 -0.122 5.20272,
+              -2.79173 -0.183 5.20272 
+            ]
+          }
+        }
+      }
+    }
+    DEF Center Transform {
+      translation 0 -1 0
+      scale 1.11653 1.11653 1.11653
+      children Shape {
+        appearance Appearance {
+          material Material {
+          }
+        }
+        geometry Box {
+          size 5 1.5 5
+        }
+      }
+    }
+    DEF Rotor_4 Transform {
+      translation -10 0 10
+      scale 0.999617 0.999617 0.999617
+      children Shape {
+        appearance Appearance {
+          material Material {
+            specularColor 0.3 0.3 0.3
+            shininess 0.3
+            diffuseColor 0.6163 0.6163 0.6163
+            ambientIntensity 0.9551
+          }
+        }
+        geometry IndexedFaceSet {
+          creaseAngle 1
+          coordIndex [
+            78, 171, 172, 63, -1, 
+            74, 163, 164, 67, -1, 
+            62, 175, 63, 172, 64, 170, 193, 65, 168, 66, 166, 67, 164, 68, 162, 69, 70, 173, -1, 
+            165, 74, 67, 166, -1, 
+            173, 70, 71, 174, -1, 
+            175, 62, 79, 176, -1, 
+            167, 75, 66, 168, -1, 
+            175, 176, 78, 63, -1, 
+            73, 161, 162, 68, -1, 
+            77, 169, 170, 64, -1, 
+            62, 173, 174, 79, -1, 
+            75, 165, 166, 66, -1, 
+            174, 71, 72, 161, 73, 163, 74, 165, 75, 167, 76, 192, 169, 77, 171, 78, 176, 79, -1, 
+            163, 73, 68, 164, -1, 
+            171, 77, 64, 172, -1, 
+            192, 76, 65, 193, -1, 
+            169, 192, 193, 170, -1, 
+            161, 72, 69, 162, -1, 
+            72, 71, 70, 69, -1, 
+            76, 167, 168, 65, -1, 
+            -1 
+          ]
+          coord Coordinate {
+            point [
+              1.87355 -2.12 -0.139033,
+              0.783522 -2.076 0.446909,
+              0.783515 -2.267 0.566909,
+              0.783572 -2.266 -0.517091,
+              1.87352 -2.12 0.566967,
+              1.80752 -2.12 0.566963,
+              1.87359 -2.266 -0.877033,
+              1.87355 -2.267 -0.047033,
+              1.87352 -2.267 0.566967,
+              1.80752 -2.267 0.566963,
+              1.80755 -2.12 -0.129037,
+              1.80755 -2.267 -0.037037,
+              1.80759 -2.266 -0.867037,
+              1.80659 -2.12 -0.874037,
+              1.87259 -2.12 -0.884034,
+              -1.18645 -2.12 -0.139194,
+              -1.18541 -2.12 -0.884194,
+              -1.11941 -2.12 -0.874191,
+              -1.12041 -2.266 -0.867191,
+              -1.12045 -2.12 -0.129191,
+              -1.12048 -2.12 0.566809,
+              -1.12048 -2.267 0.566809,
+              -1.18649 -2.267 0.566806,
+              -1.18645 -2.267 -0.047194,
+              -1.12045 -2.267 -0.037191,
+              -1.18641 -2.266 -0.877194,
+              -1.18649 -2.12 0.566806,
+              -0.096428 -2.266 -0.517137,
+              -0.096485 -2.267 0.566863,
+              -0.096479 -2.076 0.446863,
+              0.591406 -3.166 2.6379,
+              0.095406 -3.166 2.63787,
+              0.095406 -2.912 2.63787,
+              0.219395 -3.166 2.85388,
+              0.219395 -2.912 2.85388,
+              0.467395 -2.912 2.85389,
+              0.467395 -3.166 2.85389,
+              0.467418 -2.912 2.42289,
+              0.219418 -2.912 2.42288,
+              0.591406 -2.912 2.6379,
+              0.219418 -3.166 2.42288,
+              0.467418 -3.166 2.42289,
+              0.434395 -3.132 2.85389,
+              0.252395 -3.132 2.85388,
+              0.252395 -2.946 2.85388,
+              0.434395 -2.946 2.85389,
+              0.269336 -3.076 3.96788,
+              0.417336 -3.129 3.96789,
+              0.417336 -3.076 3.96789,
+              0.269336 -3.129 3.96788,
+              0.269395 -3.012 2.85388,
+              0.269395 -3.066 2.85388,
+              0.367395 -2.962 2.85389,
+              0.319395 -2.962 2.85388,
+              0.417395 -3.066 2.85389,
+              0.417395 -3.012 2.85389,
+              0.367336 -3.179 3.96789,
+              0.319336 -3.179 3.96789,
+              0.319395 -3.116 2.85388,
+              0.367395 -3.116 2.85389,
+              0.319336 -3.026 3.96789,
+              0.367336 -3.026 3.96789,
+              6.61556 0.193 -0.215784,
+              5.14735 -0.086 3.80614,
+              1.43223 -0.234 5.94594,
+              -4.46066 -0.086 3.80563,
+              -5.92844 0.192 -0.216444,
+              -4.46123 0.471 -4.23737,
+              -0.74512 0.619 -6.37717,
+              3.47884 0.568 -5.63495,
+              5.14777 0.471 -4.23786,
+              5.14777 0.532 -4.23786,
+              3.47884 0.628 -5.63495,
+              -0.74512 0.68 -6.37717,
+              -4.46123 0.531 -4.23737,
+              -5.92844 0.253 -0.216444,
+              -4.46066 -0.025 3.80563,
+              1.43223 -0.173 5.94594,
+              5.14735 -0.025 3.80614,
+              6.61556 0.253 -0.215784,
+              0.614972 0.679 -8.1101,
+              0.614936 0.106 -7.4281,
+              0.614936 -1.196 -7.4281,
+              0.614972 -1.767 -8.1101,
+              0.615018 -1.768 -9.0011,
+              0.615054 -1.196 -9.6831,
+              0.615062 -0.319 -9.8381,
+              0.615054 0.106 -9.6831,
+              0.615039 0.453 -9.3931,
+              0.615018 0.679 -9.0011,
+              0.530019 0.679 -9.0011,
+              0.530039 0.453 -9.39311,
+              0.530054 0.106 -9.68311,
+              0.530062 -0.319 -9.83811,
+              0.530054 -1.196 -9.68311,
+              0.530019 -1.768 -9.0011,
+              0.529972 -1.767 -8.1101,
+              0.529936 -1.196 -7.4281,
+              0.529928 -0.319 -7.2731,
+              0.529936 0.106 -7.4281,
+              0.529972 0.679 -8.1101,
+              0.255231 -2.14915 -7.3791,
+              0.758162 -2.59984 3.36791,
+              0.594847 -2.54881 3.72511,
+              -0.062854 -2.59984 3.36787,
+              0.594839 -1.93645 3.87253,
+              0.100415 -1.93645 3.8725,
+              0.75818 -1.70965 3.02771,
+              -0.062836 -1.70965 3.02767,
+              0.758223 -1.02925 2.19989,
+              -0.062793 -1.02925 2.19985,
+              0.758299 -0.830803 0.75404,
+              -0.062717 -0.830803 0.753997,
+              0.758301 -0.314833 0.72002,
+              -0.062715 -0.314833 0.719977,
+              0.758416 -0.415926 -1.4647,
+              -0.0626 -0.415926 -1.46475,
+              -0.062585 -0.937566 -1.74258,
+              0.477454 -1.87132 -6.6023,
+              0.214366 -1.87132 -6.60231,
+              0.441263 -0.495408 -8.43416,
+              0.250751 -0.495408 -8.43417,
+              0.414074 -0.461388 -8.95013,
+              0.277994 -0.461388 -8.95014,
+              0.436671 -2.14915 -7.37909,
+              0.4548 -2.34193 -7.08992,
+              0.241608 -2.34193 -7.08993,
+              0.758426 -3.16939 -1.65658,
+              -0.06259 -3.16939 -1.65662,
+              0.758217 -3.03428 2.31419,
+              -0.062799 -3.03428 2.31415,
+              -0.062716 -1.54522 0.742657,
+              -0.062569 -1.57261 -2.04875,
+              0.7583 -1.54522 0.7427,
+              0.758431 -0.937566 -1.74253,
+              0.758447 -1.57261 -2.04871,
+              0.100423 -2.54881 3.72509,
+              -0.476109 -1.54522 0.742637,
+              -0.47611 -0.830803 0.753977,
+              -0.063333 -1.54522 0.742658,
+              -0.063334 -0.830803 0.753998,
+              -0.475978 -0.937566 -1.74259,
+              -0.063202 -0.937566 -1.74257,
+              1.17046 -0.830803 0.754063,
+              0.757682 -0.830803 0.754041,
+              1.17064 -1.59392 -2.71303,
+              1.17046 -1.54522 0.742723,
+              0.757683 -1.54522 0.742701,
+              0.75783 -1.57261 -2.04871,
+              1.17059 -0.937566 -1.74251,
+              -0.475928 -1.57816 -2.70774,
+              -0.475962 -1.57261 -2.04878,
+              -0.063153 -0.955725 -2.674,
+              -0.475929 -0.955725 -2.67402,
+              -0.063186 -1.57261 -2.04875,
+              -0.063152 -1.57816 -2.70772,
+              1.17061 -1.57261 -2.04869,
+              1.17064 -0.971488 -2.67932,
+              0.757865 -1.59392 -2.71305,
+              0.757814 -0.937566 -1.74253,
+              0.757863 -0.971488 -2.67934,
+              1.43188 0.68 -6.37806,
+              1.43188 0.619 -6.37806,
+              -2.79216 0.628 -5.63428,
+              -2.79216 0.567 -5.63428,
+              -5.55033 0.401 -2.35642,
+              -5.55033 0.34 -2.35642,
+              -5.54956 0.105 1.92358,
+              -5.54956 0.044 1.92358,
+              -0.744768 -0.173 5.94583,
+              -0.744768 -0.234 5.94583,
+              3.47927 -0.122 5.20305,
+              3.47927 -0.183 5.20305,
+              6.23667 0.341 -2.3568,
+              6.23667 0.402 -2.3568,
+              6.23644 0.044 1.9242,
+              6.23644 0.105 1.9242,
+              0.530062 -0.771 -9.83811,
+              0.615062 -0.771 -9.8381,
+              0.530039 -1.542 -9.3921,
+              0.615039 -1.542 -9.3921,
+              0.529995 -1.846 -8.5551,
+              0.614995 -1.846 -8.5551,
+              0.529951 -1.542 -7.7181,
+              0.614951 -1.542 -7.7181,
+              0.529928 -0.771 -7.2731,
+              0.614928 -0.771 -7.2731,
+              0.614928 -0.319 -7.2731,
+              0.529951 0.453 -7.7181,
+              0.614951 0.453 -7.7181,
+              0.614995 0.757 -8.5551,
+              0.529995 0.757 -8.5551,
+              -2.79173 -0.122 5.20272,
+              -2.79173 -0.183 5.20272 
+            ]
+          }
+        }
+      }
+    }
+  ]
+}
+Background {
+  skyColor [
+    0.76238 0.8 0.1427,
+    0.277798 0.219779 0.7,
+    0.222549 0.390234 0.7,
+    0.60094 0.662637 0.69 
+  ]
+  skyAngle [0.1, 1.2, 1.57]
+  groundColor [
+    0 0.8 0,
+    0.174249 0.82 0.187362,
+    0.467223 0.82 0.445801,
+    0.621997 0.67 0.600279 
+  ]
+  groundAngle [0.9, 1.5, 1.57]
+}
+DEF sqare_platform Transform {
+  translation 0 -0.432 0
+  scale 2 0.04 2
+  children [
+    Shape {
+      appearance Appearance {
+        material Material {
+          diffuseColor 0.8 0.407144 0.297047
+        }
+      }
+      geometry Box {
+      }
+    }
+    Transform {
+      translation 0 0.031 0
+      scale 0.5 1 0.5
+      children Shape {
+        appearance Appearance {
+          material Material {
+            diffuseColor 0.8 0.613697 0.365273
+          }
+        }
+        geometry Cylinder {
+        }
+      }
+    }
+  ]
+}
\ No newline at end of file
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl.bak b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl.bak
new file mode 100644
index 0000000000000000000000000000000000000000..eb0ece0c87dd94275cc01905e42ff20b87bd800c
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl.bak
@@ -0,0 +1,1030 @@
+#VRML V2.0 utf8
+
+#Created with V-Realm Builder v2.0
+#Integrated Data Systems Inc.
+#www.ids-net.com
+
+
+PointLight {
+	location	-0.8 1 1
+}
+PointLight {
+	location	1.1 1.1 0
+}
+DEF Viewport_heli Viewpoint {
+	fieldOfView	0.785398
+	orientation	1 0 0  0.188496
+	position	0.024 -0.191 11.9975
+}
+DEF Helicopter Transform {
+	translation	0 0 0
+	scale	0.108 0.108 0.108
+	children [ 
+	    DEF Rotor_1 Transform {
+		    translation	10 0 10
+		    scale	1.00001 1.00001 1.00001
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    color	NULL
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+				    colorIndex	[  ]
+			    }
+
+		    }
+	    }
+
+	    DEF Rotor_2 Transform {
+		    translation	10 0 -10
+		    scale	0.999617 0.999617 0.999617
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+			    }
+
+		    }
+	    }
+
+	    DEF Rotor_3 Transform {
+		    translation	-10 0 -10
+		    scale	0.999617 0.999617 0.999617
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+			    }
+
+		    }
+	    }
+
+	    DEF Center Transform {
+		    translation	0 -1 0
+		    scale	1.11653 1.11653 1.11653
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+				    }
+
+			    }
+
+			    geometry	Box {
+				    size	5 1.5 5
+			    }
+
+		    }
+	    }
+
+	    DEF Rotor_4 Transform {
+		    translation	-10 0 10
+		    scale	0.999617 0.999617 0.999617
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+			    }
+
+		    }
+	    }
+	]
+}
+Background {
+	groundAngle	[ 0.9, 1.5, 1.57 ]
+	groundColor	[ 0 0.8 0,
+			  0.174249 0.82 0.187362,
+			  0.467223 0.82 0.445801,
+			  0.621997 0.67 0.600279 ]
+	skyAngle	[ 0.1, 1.2, 1.57 ]
+	skyColor	[ 0.76238 0.8 0.1427,
+			  0.277798 0.219779 0.7,
+			  0.222549 0.390234 0.7,
+			  0.60094 0.662637 0.69 ]
+}
+DEF sqare_platform Transform {
+	translation	0 -0.432 0
+	scale	2 0.04 2
+	children [ 
+	    Shape {
+		    appearance	Appearance {
+			    material	Material {
+				    ambientIntensity	0.2
+				    diffuseColor	0.8 0.407144 0.297047
+			    }
+
+		    }
+
+		    geometry	Box {
+		    }
+
+	    }
+
+	    Transform {
+		    translation	0 0.031 0
+		    scale	0.5 1 0.5
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    diffuseColor	0.8 0.613697 0.365273
+				    }
+
+			    }
+
+			    geometry	Cylinder {
+			    }
+
+		    }
+	    }
+	]
+}
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl.thumbnail.png b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl.thumbnail.png
new file mode 100644
index 0000000000000000000000000000000000000000..4231e2d42a6d0f0dc58ca9f49fe45912d07a265d
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logged_playback.wrl.thumbnail.png differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logs_vs_simulation.slx b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logs_vs_simulation.slx
new file mode 100644
index 0000000000000000000000000000000000000000..bb46aae242046dad1c49bace57bfb2190ddca165
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/logs_vs_simulation.slx differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/lqr_quad_gains.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/lqr_quad_gains.m
new file mode 100644
index 0000000000000000000000000000000000000000..995bbadcb65c90a009e94d53568baf020ad9df1d
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/lqr_quad_gains.m
@@ -0,0 +1,283 @@
+function [U] = lqr_quad_gains(X)
+% Name: lqr_gains
+% Author: Phillip Jones.
+% Description: Compute control command for CrazyFlie quad (-KX), 
+%              based on LQR control law
+%
+%
+%   X_dot = A*X + B*U;
+%
+%   Where, A is linerized quadcopter body dynmaics
+%          B is the linearized actuator dynamics
+%
+%   Non-linear
+%
+% Dynamic equation for a quadcopter (Bolandil-ICA-2013)
+%         x1  = x
+%         x2  = y
+%         x3  = z
+%         x4  = phi
+%         x5  = theta
+%   X  =  x6  = psi
+%         x7  = x_dot
+%         x8  = y_dot
+%         x9  = z_dot
+%         x10 = phi_dot
+%         x11 = theta_dot
+%         x12 = psi_dot
+%
+%
+%             x1_dot  = x7
+%             x2_dot  = x8
+%             x3_dot  = x9
+%             x4_dot  = x10
+%             x5_dot  = x11
+%   X_dot  =  x6_dot  = x12
+%             x7_dot  = x_ddot     = -(sin(theta)*cos(phi))*(u1/m) 
+%                                  = -(sin(x5)*cos(x4))*(u1/m)
+%
+%             x8_dot  = y_ddot     = sin(phi)*(u1/m)
+%                                  = sin(x4)*(u1/m)
+%
+%             x9_dot  = z_ddot     = -(cos(theta)*cos(phi))*(u1/m) + g
+%                                  = -(cos(x5)*cos(x4))*(u1/m) + g
+%
+%             x10_dot = phi_ddot   =   -psi_dot*theta_dot*cos(phi)
+%                                    + [len*cos(psi)*u2]/I_xx
+%                                    - [len*sin(psi)*u3]/I_yy
+%                                    + [(I_yy - I_zz)/I_xx]*(psi_dot - theta_dot*sin(phi))*(theta_dot*cos(phi))
+%
+%                                  =   -x12*x11*cos(x4)
+%                                    + [len*cos(x6)*u2]/I_xx
+%                                    - [len*sin(x6)*u3]/I_yy
+%                                    + [(I_yy - I_zz)/I_xx]*(x12 - x11*sin(x4))*(x11*cos(x4))
+%
+%             x11_dot = theta_ddot =   (psi_dot*phi_dot)/cos(phi) + phi_dot*theta_dot*tan(phi) 
+%                                    + [len*(sin(psi)/cos(phi))*u2]/I_xx 
+%                                    + [len*(cos(psi)/cos(phi))*u3]/I_yy 
+%                                    - [(I_yy - I_zz)/I_xx]*(psi_dot - theta_dot*sin(phi))*(phi_dot/cos(phi))
+%
+%                                  =   (x12*x10)/cos(x4) + x10*x11*tan(x4)
+%                                    + [len*(sin(x6)/cos(x4))*u2]/I_xx 
+%                                    + [len*(cos(x6)/cos(x4))*u3]/I_yy
+%                                    - [(I_yy - I_zz)/I_xx]*(x12 - x11*sin(x4))*(x10/cos(x4))
+%
+%             x12_dot = psi_ddot   =   phi_dot*psi_dot*tan(phi) + (phi_dot*theta_dot)/cos(phi) 
+%                                    + [len*sin(psi)*tan(phi)*u2]/I_xx
+%                                    + [len*cos(psi)*tan(phi)*u3]/I_yy 
+%                                    + [len*u4]/I_zz 
+%                                    - [(I_yy - I_zz)/I_xx]*(psi_dot - theta_dot*sin(phi))*(phi_dot*tan(phi))
+%
+%                                  =   x10*x12*tan(x4) + (x10*x11)/cos(x4) 
+%                                    + [len*sin(x6)*tan(x4)*u2]/I_xx 
+%                                    + [len*cos(x6)*tan(x4)*u3]/I_yy 
+%                                    + [len*u4]/I_zz 
+%                                    - [(I_yy - I_zz)/I_xx]*(x12 - x11*sin(x4))*(x10*tan(x4))
+%
+%
+%
+% Linear (assume operating all states at or near 0)
+%
+%             x1_dot  = x7
+%             x2_dot  = x8
+%             x3_dot  = x9
+%             x4_dot  = x10
+%             x5_dot  = x11
+%   X_dot  =  x6_dot  = x12
+%             x7_dot  = x_ddot     = -(theta)*(u1/m) = -(theta)*(g)  (at equil u1 ~ g*m)
+%                                  = -(x5)*(u1/m)    = -(x5)*(g)
+%
+%             x8_dot  = y_ddot     = (phi)*(u1/m) = (phi)*(u1)  (at equil u1 ~ g*m)
+%                                  = (x4)*(u1/m)  = (x4)*(g)
+%
+%             x9_dot  = z_ddot     = -(u1/m) + g  = -u1/m  (at equilibrium u1 is u1+g*m)
+%                                  = -(u1/m) + g  = -u1/m
+%
+%             x10_dot = phi_ddot   =   [len*u2]/I_xx
+%                                  =   [len*u2]/I_xx
+%
+%             x11_dot = theta_ddot =   [len*u3]/I_yy 
+%                                  =   [len*u3]/I_yy
+%
+%             x12_dot = psi_ddot   =   [len*u4]/I_zz 
+%                                  =   [len*u4]/I_zz 
+%
+%     Matrix A :
+%       x   y   z   phi theta psi x_dot y_dot z_dot phi_dot theta_dot psi_dot    
+%       x1  x2  x3  x4   x5   x6   x7    x8    x9     x10      x11    x12
+% A = [ 0   0   0   0    0    0    1     0     0      0        0      0; ...
+%       0   0   0   0    0    0    0     1     0      0        0      0; ...
+%       0   0   0   0    0    0    0     0     1      0        0      0; ...
+%       0   0   0   0    0    0    0     0     0      1        0      0; ...
+%       0   0   0   0    0    0    0     0     0      0        1      0; ...
+%       0   0   0   0    0    0    0     0     0      0        0      1; ...
+%       0   0   0   0   -g    0    0     0     0      0        0      0; ...
+%       0   0   0   g    0    0    0     0     0      0        0      0; ...
+%       0   0   0   0    0    0    0     0     0      0        0      0; ...
+%       0   0   0   0    0    0    0     0     0      0        0      0; ...
+%       0   0   0   0    0    0    0     0     0      0        0      0; ...
+%       0   0   0   0    0    0    0     0     0      0        0      0]
+%
+%   Matrix B :
+%       u1       u2        u3         u4
+% B = [ 0        0         0          0; ...    % x1_dot  (x_dot) 
+%       0        0         0          0; ...    % x2_dot  (y_dot)
+%       0        0         0          0; ...    % x3_dot  (z_dot)
+%       0        0         0          0; ...    % x4_dot  (phi_dot)
+%       0        0         0          0; ...    % x5_dot  (theta_dot)
+%       0        0         0          0; ...    % x6_dot  (psi_dot)
+%       0        0         0          0; ...    % x7_dot  (x_ddot)
+%       0        0         0          0; ...    % x8_dot  (y_ddot)
+%      -1/m      0         0          0; ...    % x9_dot  (z_ddot)
+%       0   len_xy/I_xx    0          0; ...    % x10_dot (phi_ddot)
+%       0        0     len_xy/I_yy    0; ...    % x11_dot (theta_ddot)
+%       0        0         0       len/I_zz ]   % x12_dot (psi_ddot)
+%
+%  Where CrazyFlie constants are:
+%  g = 9.8;        % (m/s^2) Gravity
+%  m = 28/1000;    % (Kg) Mass of quad (Crazyflie max take-off weight  ~42g) (Foster-2015)
+%  len = (.092/2); % (m) Length of quad lever arm for yaw force (92mm diameter of CrazyFlie)
+%  len_xy = (.092/2)*sin(pi/4); % (m) Length of quad lever arm for pitch/roll force: Quad arm length * projection onto pitch/roll axis
+%  I_xx = 1.33e-5; % (Kg*m^2) Moment of inertia about X-axis (McInerney-MS-Thesis-2017)
+%  I_yy = 1.33e-5; % (Kg*m^2) Moment of inertia about Y-axis (McInerney-MS-Thesis-2017)
+%  I_zz = 2.64e-5; % (Kg*m^2) Moment of inertia about Z-axis (McInerney-MS-Thesis-2017)
+%
+%  LQR: Q and R matrix (Note the Q and R matrix is differnt from the Q and
+%       R in LQR.
+%
+%  Q = [1  0  0  0  0  0  0  0  0  0  0  0; ...
+%       0  1  0  0  0  0  0  0  0  0  0  0; ...
+%       0  0  1  0  0  0  0  0  0  0  0  0; ...
+%       0  0  0  1  0  0  0  0  0  0  0  0; ...
+%       0  0  0  0  1  0  0  0  0  0  0  0; ...
+%       0  0  0  0  0  1  0  0  0  0  0  0; ...
+%       0  0  0  0  0  0  1  0  0  0  0  0; ...
+%       0  0  0  0  0  0  0  1  0  0  0  0; ...
+%       0  0  0  0  0  0  0  0  1  0  0  0; ...
+%       0  0  0  0  0  0  0  0  0  1  0  0; ...
+%       0  0  0  0  0  0  0  0  0  0  1  0; ...
+%       0  0  0  0  0  0  0  0  0  0  0  1]
+%
+%  R = [1  0  0  0; ...
+%       0  1  0  0; ...
+%       0  0  1  0; ...
+%       0  0  0  1]
+
+% K from matlab lqr function: [K, S, E] = lqr(A, B, Q, R)  (Continuous time)
+
+K = [ 0.0000    0.0000   -1.0000    0.0000   -0.0000    0.0000    0.0000    0.0000   -1.0276    0.0000   -0.0000    0.0000; ...
+      0.0000    1.0000   -0.0000    5.4330   -0.0000    0.0000    0.0000    1.4522    0.0000    1.0022    0.0000    0.0000; ...
+     -1.0000    0.0000   -0.0000    0.0000    5.4330   -0.0000   -1.4522    0.0000   -0.0000    0.0000    1.0022   -0.0000; ...
+      0.0000   -0.0000   -0.0000   -0.0000   -0.0000    1.0000    0.0000   -0.0000   -0.0000   -0.0000   -0.0000    1.0006];
+
+
+% K from matlab lqrd function: [K, S, E] = lqr(A, B, Q, R,Ts)  (Discrete time)
+% where Ts = .001 seconds
+dK_u_1111 = [ 0.0000   -0.0000   -0.9819    0.0000   -0.0000   -0.0000    0.0000    0.0000   -1.0095    0.0000    0.0000   -0.0000; ...
+             -0.0000    0.4076   -0.0000    2.2178    0.0000   -0.0000   -0.0000    0.5921   -0.0000    0.4098    0.0000   -0.0000; ...
+             -0.4076   -0.0000    0.0000   -0.0000    2.2178   -0.0000   -0.5921   -0.0000    0.0000   -0.0000    0.4098   -0.0000; ...
+             -0.0000   -0.0000    0.0000   -0.0000    0.0000    0.5021   -0.0000   -0.0000    0.0000   -0.0000    0.0000    0.5027];
+
+dK_u_2111 = [-0.0000   -0.0000   -0.6979   -0.0000   -0.0000    0.0000    0.0000   -0.0000   -0.7254    0.0000   -0.0000    0.0000; ...
+             -0.0000    0.4076    0.0000    2.2178    0.0000    0.0000   -0.0000    0.5921   -0.0000    0.4098   -0.0000    0.0000; ...
+             -0.4076   -0.0000    0.0000   -0.0000    2.2178    0.0000   -0.5921   -0.0000    0.0000    0.0000    0.4098    0.0000; ...
+              0.0000    0.0000   -0.0000    0.0000   -0.0000    0.5021    0.0000    0.0000    0.0000    0.0000   -0.0000    0.5027];
+
+
+dK_u_10_1_1_1 = [ 0.0000    0.0000   -0.3143    0.0000    0.0000   -0.0000   -0.0000   -0.0000   -0.3412    0.0000    0.0000   -0.0000; ...
+                  0.0000    0.4076   -0.0000    2.2178   -0.0000   -0.0000    0.0000    0.5921   -0.0000    0.4098   -0.0000   -0.0000; ...
+                 -0.4076   -0.0000   -0.0000   -0.0000    2.2178   -0.0000   -0.5921    0.0000   -0.0000    0.0000    0.4098   -0.0000; ...
+                 -0.0000   -0.0000    0.0000   -0.0000    0.0000    0.5021   -0.0000   -0.0000    0.0000   -0.0000    0.0000    0.5027];
+
+
+dK_u_10_10_10_1 = [-0.0000    0.0000   -0.3143    0.0000    0.0000   -0.0000   -0.0000    0.0000   -0.3412    0.0000    0.0000   -0.0000; ...
+                    0.0000    0.2235   -0.0000    1.2186   -0.0000    0.0000    0.0000    0.3248   -0.0000    0.2257    0.0000    0.0000; ...
+                   -0.2235    0.0000    0.0000   -0.0000    1.2186   -0.0000   -0.3248    0.0000   -0.0000   -0.0000    0.2257   -0.0000; ...
+                    0.0000    0.0000    0.0000    0.0000   -0.0000    0.5021    0.0000    0.0000    0.0000    0.0000    0.0000    0.5027];
+
+
+dK_u_10_10_10_xang_01_01_1 = [-0.0000    0.0000   -0.3143   -0.0000    0.0000    0.0000   -0.0000    0.0000   -0.3412   -0.0000    0.0000    0.0000; ...
+                               0.0000    0.2235    0.0000    1.1971    0.0000   -0.0000   -0.0000    0.3233   -0.0000    0.2256   -0.0000   -0.0000; ...
+                              -0.2235    0.0000   -0.0000    0.0000    1.1971   -0.0000   -0.3233    0.0000   -0.0000   -0.0000    0.2256   -0.0000; ...
+                               0.0000   -0.0000   -0.0000   -0.0000   -0.0000    0.5021    0.0000   -0.0000   -0.0000   -0.0000   -0.0000    0.5027];
+
+dK_u_10_10_10_xang_001_001_1 = [-0.0000   -0.0000   -0.3143   -0.0000    0.0000    0.0000   -0.0000   -0.0000   -0.3412   -0.0000    0.0000   -0.0000; ...
+                                -0.0000    0.2235    0.0000    1.1950    0.0000   -0.0000   -0.0000    0.3232    0.0000    0.2256    0.0000   -0.0000; ...
+                                -0.2235   -0.0000   -0.0000    0.0000    1.1950    0.0000   -0.3232   -0.0000   -0.0000    0.0000    0.2256   -0.0000; ...
+                                -0.0000   -0.0000   -0.0000   -0.0000    0.0000    0.5021   -0.0000   -0.0000   -0.0000   -0.0000    0.0000    0.5027];
+
+
+dK_u_10_10_10_xang_001_001_1_vang_01_01_1 = [ 0.0000    0.0000   -0.3143   -0.0000    0.0000   -0.0000   -0.0000    0.0000   -0.3412   -0.0000    0.0000   -0.0000; ...
+                                             -0.0000    0.2799    0.0000    0.7962    0.0000   -0.0000   -0.0000    0.3519   -0.0000    0.0921    0.0000   -0.0000; ...
+                                             -0.2799   -0.0000    0.0000   -0.0000    0.7962   -0.0000   -0.3519   -0.0000   -0.0000    0.0000    0.0921    0.0000; ...
+                                              0.0000    0.0000    0.0000   -0.0000   -0.0000    0.5021    0.0000    0.0000    0.0000   -0.0000   -0.0000    0.5027];
+
+
+dK_u_10_10_10_xang_0001_0001_1_vang_005_005_1 = [ 0.0000    0.0000   -0.3143   -0.0000   -0.0000    0.0000    0.0000    0.0000   -0.3412   -0.0000   -0.0000    0.0000; ...
+                                                  0.0000    0.2892    0.0000    0.6883    0.0000    0.0000    0.0000    0.3525    0.0000    0.0689    0.0000    0.0000; ...
+                                                 -0.2892    0.0000    0.0000    0.0000    0.6883    0.0000   -0.3525   -0.0000    0.0000    0.0000    0.0689    0.0000; ...
+                                                 -0.0000    0.0000   -0.0000    0.0000    0.0000    0.5021   -0.0000    0.0000   -0.0000    0.0000    0.0000    0.5027];
+
+dK_u_10_10_10_xang_0001_0001_1_vang_005_005_1_v_01_01_1 = [-0.0000   -0.0000   -0.3143   -0.0000    0.0000    0.0000   -0.0000   -0.0000   -0.3412   -0.0000    0.0000   -0.0000; ...
+                                                           -0.0000    0.2896   -0.0000    0.5086    0.0000   -0.0000   -0.0000    0.1961    0.0000    0.0679    0.0000   -0.0000; ...
+                                                           -0.2896    0.0000   -0.0000   -0.0000    0.5086   -0.0000   -0.1961    0.0000   -0.0000    0.0000    0.0679    0.0000; ...
+                                                           -0.0000    0.0000    0.0000   -0.0000   -0.0000    0.5021   -0.0000   -0.0000   -0.0000   -0.0000    0.0000    0.5027];
+
+dK_u_10_10_10_xang_0001_0001_1_vang_005_005_1_v_01_01_01 = [ 0.0000   -0.0000   -0.3153    0.0000   -0.0000    0.0000    0.0000    0.0000   -0.1661    0.0000   -0.0000    0.0000; ...
+                                                            -0.0000    0.2896   -0.0000    0.5086   -0.0000   -0.0000    0.0000    0.1961   -0.0000    0.0679   -0.0000   -0.0000; ...
+                                                            -0.2896   -0.0000    0.0000   -0.0000    0.5086   -0.0000   -0.1961   -0.0000    0.0000   -0.0000    0.0679   -0.0000; ...
+                                                             0.0000   -0.0000   -0.0000   -0.0000   -0.0000    0.5021    0.0000    0.0000   -0.0000   -0.0000   -0.0000    0.5027];
+
+dK_u_10_50_50_xang_0001_0001_1_vang_005_005_1_v_01_01_01 = [-0.0000   -0.0000   -0.3153   -0.0000    0.0000   -0.0000   -0.0000   -0.0000   -0.1661   -0.0000    0.0000    0.0000; ...
+                                                            -0.0000    0.1356    0.0000    0.2444    0.0000   -0.0000   -0.0000    0.0928    0.0000    0.0335    0.0000   -0.0000; ...
+                                                            -0.1356   -0.0000   -0.0000   -0.0000    0.2444    0.0000   -0.0928   -0.0000   -0.0000   -0.0000    0.0335    0.0000; ...
+                                                            -0.0000   -0.0000    0.0000   -0.0000    0.0000    0.5021   -0.0000   -0.0000    0.0000   -0.0000    0.0000    0.5027];
+
+dK_u_10_100_100_xang_0001_0001_1_vang_005_005_1_v_01_01_01 = [ 0.0000   -0.0000   -0.3153   -0.0000   -0.0000   -0.0000   -0.0000   -0.0000   -0.1661    0.0000   -0.0000   -0.0000; ...
+                                                               0.0000    0.0970    0.0000    0.1781   -0.0000    0.0000   -0.0000    0.0668   -0.0000    0.0248   -0.0000   -0.0000; ...
+                                                              -0.0970   -0.0000    0.0000    0.0000    0.1781   -0.0000   -0.0668   -0.0000    0.0000   -0.0000    0.0248    0.0000; ...
+                                                              -0.0000    0.0000    0.0000    0.0000   -0.0000    0.5021    0.0000    0.0000    0.0000   -0.0000    0.0000    0.5027];
+
+dK_u_10_500_500_xang_0001_0001_1_vang_005_005_1_v_01_01_01 = [-0.0000   -0.0000   -0.3153    0.0000   -0.0000    0.0000    0.0000    0.0000   -0.1661    0.0000   -0.0000    0.0000; ...
+                                                              -0.0000    0.0440   -0.0000    0.0871    0.0000   -0.0000    0.0000    0.0312   -0.0000    0.0130    0.0000   -0.0000; ...
+                                                              -0.0440   -0.0000    0.0000   -0.0000    0.0871   -0.0000   -0.0312   -0.0000    0.0000    0.0000    0.0130    0.0000; ...
+                                                               0.0000   -0.0000    0.0000    0.0000   -0.0000    0.5021    0.0000   -0.0000   -0.0000   -0.0000   -0.0000    0.5027];
+
+
+dK_u_50_500_500_xang_0001_0001_1_vang_005_005_1_v_01_01_01 = [ 0.0000   -0.0000   -0.1412   -0.0000   -0.0000    0.0000    0.0000   -0.0000   -0.0995   -0.0000   -0.0000    0.0000; ...
+                                                              -0.0000    0.0440    0.0000    0.0871    0.0000   -0.0000   -0.0000    0.0312    0.0000    0.0130    0.0000   -0.0000; ...
+                                                              -0.0440    0.0000    0.0000    0.0000    0.0871    0.0000   -0.0312    0.0000    0.0000    0.0000    0.0130    0.0000; ...
+                                                              -0.0000    0.0000    0.0000    0.0000    0.0000    0.5021   -0.0000   -0.0000   -0.0000   -0.0000   -0.0000    0.5027];
+
+
+dK_u_50_500_500_xang_0001_0001_1_vang_005_005_1_v_01_01_005 = [ 0.0000    0.0000   -0.1412    0.0000    0.0000   -0.0000    0.0000    0.0000   -0.0944    0.0000    0.0000   -0.0000; ...
+                                                               -0.0000    0.0440   -0.0000    0.0871    0.0000    0.0000   -0.0000    0.0312   -0.0000    0.0130    0.0000    0.0000; ...
+                                                               -0.0440    0.0000   -0.0000    0.0000    0.0871   -0.0000   -0.0312    0.0000   -0.0000    0.0000    0.0130   -0.0000; ...
+                                                               -0.0000    0.0000    0.0000    0.0000    0.0000    0.5021   -0.0000    0.0000    0.0000    0.0000   -0.0000    0.5027];
+
+
+dK_u_50_500_500_xang_0001_0001_1_vang_005_005_1_v_01_01_001 = [-0.0000   -0.0000   -0.1412    0.0000   -0.0000   -0.0000    0.0000   -0.0000   -0.0900    0.0000   -0.0000   -0.0000; ...
+                                                               -0.0000    0.0440   -0.0000    0.0871    0.0000   -0.0000   -0.0000    0.0312   -0.0000    0.0130   -0.0000   -0.0000; ...
+                                                               -0.0440    0.0000    0.0000   -0.0000    0.0871    0.0000   -0.0312   -0.0000    0.0000    0.0000    0.0130   -0.0000; ...
+                                                               -0.0000   -0.0000    0.0000    0.0000    0.0000    0.5021   -0.0000   -0.0000    0.0000   -0.0000   -0.0000    0.5027];
+
+
+dK_u_100_500_500_xang_0001_0001_1_vang_005_005_1_v_01_01_001 = [ 0.0000    0.0000   -0.0999    0.0000   -0.0000    0.0000    0.0000    0.0000   -0.0754    0.0000   -0.0000    0.0000; ...
+                                                                 0.0000    0.0440    0.0000    0.0871   -0.0000   -0.0000    0.0000    0.0312   -0.0000    0.0130   -0.0000   -0.0000; ...
+                                                                -0.0440    0.0000    0.0000    0.0000    0.0871   -0.0000   -0.0312    0.0000    0.0000   -0.0000    0.0130   -0.0000; ...
+                                                                -0.0000   -0.0000   -0.0000    0.0000   -0.0000    0.5021   -0.0000   -0.0000   -0.0000   -0.0000   -0.0000    0.5027];
+
+
+dK_488_matrix = [
+        -0.0   0.0    -0.9698 -0.0   0.0     -0.0 0.0   0.0   -1.3878 -0.0   0.0     -0.0;
+        0.0    0.9678 0.0     0 0.0     -0.0 0.0   1.429 0.0     0 0.0     -0.0;
+        0.9678 -0.0   0.0     0.0    -0 -0.0 1.429 -0.0  0.0     0.0    -0 -0.0;
+        -0.0   -0.0   0.0     -0.0   0.0     0.0  -0.0  -0.0  0.0     -0.0   0.0     0
+];
+
+
+U_col = -dK_u_100_500_500_xang_0001_0001_1_vang_005_005_1_v_01_01_001*X.';
+
+U = U_col.';
+
+end
\ No newline at end of file
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/measured_flight_path.csv b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/measured_flight_path.csv
new file mode 100644
index 0000000000000000000000000000000000000000..e035ade1d9f99991c40a5c8d5a65fd19daa5e0d5
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/measured_flight_path.csv
@@ -0,0 +1,2644 @@
+0.2176486,-0.012831502594053745,-0.05668031424283981,0.0023447335697710514,-0.009807676182234892,-0.0364507835893426,-0.001927381542599269

+0.2275457,-0.012979893945157528,-0.05700564384460449,0.0022940330673009157,-0.009446160134433506,-0.03652563219733328,-0.0017887829505459283

+0.2371692,-0.012834964320063591,-0.0567130446434021,0.0023060603998601437,-0.00985970626213302,-0.03642600977264755,-0.0019233879524124884

+0.2472733,-0.012957637198269367,-0.057041291147470474,0.0022798648569732904,-0.00943993354871124,-0.03647609880387453,-0.0017906547453365757

+0.2589816,-0.012993457727134228,-0.05696013942360878,0.0022817745339125395,-0.00990696175149401,-0.0364150902002712,-0.0018660600834105364

+0.267765,-0.012951002456247807,-0.05696839466691017,0.0023043446708470583,-0.009460168408421028,-0.036496854288526843,-0.0017704749082977057

+0.2794773,-0.012986255809664726,-0.05692688375711441,0.002269656863063574,-0.009856136863570251,-0.0364203474783953,-0.0019397053638289963

+0.2902138,-0.012944110669195652,-0.05693438649177551,0.0022897315211594105,-0.009467892533092704,-0.03653106196279195,-0.0017951546377871412

+0.2989972,-0.012979254126548767,-0.05694621428847313,0.0023265595082193613,-0.009893134291262167,-0.03648604945404304,-0.001907783739550471

+0.3121288,-0.012937863357365131,-0.05695835500955582,0.0023511743638664484,-0.009422071681826126,-0.036534282518569806,-0.0017736776131544783

+0.3188215,-0.012962453998625278,-0.05695939064025879,0.002342310966923833,-0.009894435240333767,-0.03645669590597665,-0.0018974539441052787

+0.3295575,-0.012836718000471592,-0.0566631481051445,0.0023740632459521294,-0.009463144921403573,-0.03651435079808542,-0.0017459273502321722

+0.3383416,-0.012955869548022747,-0.056971486657857895,0.0023448877036571503,-0.009883594381225082,-0.036466463317019845,-0.0018626089663306214

+0.3471259,-0.012913662008941174,-0.056981638073921204,0.0023680515587329865,-0.009466063580664336,-0.03650886726184854,-0.0017430928131401118

+0.3578618,-0.012955916114151478,-0.05695992335677147,0.0023012745659798384,-0.009841870623985692,-0.036434961697330064,-0.0018494768314666666

+0.3676226,-0.01291634701192379,-0.05696599930524826,0.0023231881204992533,-0.00938860576009195,-0.036497124268368104,-0.0017397358428780847

+0.3764103,-0.012843511067330837,-0.0566757433116436,0.002402205253019929,-0.009799248987986666,-0.036468169570187774,-0.001864259137738746

+0.3861714,-0.013006879016757011,-0.05692008137702942,0.002308568451553583,-0.009434723841064517,-0.0365535309846213,-0.0017568018848046795

+0.3969013,-0.012911156751215458,-0.0566839799284935,0.0023472618777304888,-0.00980146585936418,-0.036508674513887826,-0.001881800772527698

+0.4086144,-0.012944808229804039,-0.05667668581008911,0.002336987294256687,-0.009437587330610004,-0.036578056909641506,-0.001785638242661492

+0.4173972,-0.012903649359941483,-0.056678060442209244,0.0023627958726137877,-0.009838008625067604,-0.03652677188655967,-0.0018741562913356504

+0.4261815,-0.013026543892920017,-0.05691331624984741,0.0023079055827111006,-0.009478120322355997,-0.03662437101097038,-0.001776762211643451

+0.4378996,-0.013076789677143097,-0.05688921734690666,0.0022804019972682,-0.009805213324090744,-0.036556627012360905,-0.0019029980103092911

+0.44863,-0.012937636114656925,-0.05666625127196312,0.002267151605337858,-0.009418820969849872,-0.03661239610773148,-0.0017898936061396717

+0.4583906,-0.013013966381549835,-0.05693453550338745,0.002266873372718692,-0.009866421302550209,-0.0365058288817518,-0.0018684188003940743

+0.4691283,-0.012882670387625694,-0.05663570389151573,0.0022801454178988934,-0.009457145655811234,-0.03653850567976396,-0.0017386737575076014

+0.4779155,-0.012991812080144882,-0.056982897222042084,0.0022752315271645784,-0.00980967681573447,-0.03646522252215222,-0.0018832651368764122

+0.4866968,-0.012959334068000317,-0.05700691416859627,0.0022908805403858423,-0.009415175497158972,-0.036510872627101905,-0.001737365609138935

+0.4984059,-0.012998118996620178,-0.0569845549762249,0.0022778722923249006,-0.009855939999031399,-0.03645419854375473,-0.0018692767107064087

+0.507191,-0.012967524118721485,-0.05700751021504402,0.002296865452080965,-0.00947200098322874,-0.03651221315425199,-0.0017295118489011416

+0.5179623,-0.013025909662246704,-0.0569673590362072,0.002268504351377487,-0.009831446682874329,-0.0364250078162455,-0.0018805647911546634

+0.526715,-0.012991486117243767,-0.05698741227388382,0.0022903706412762403,-0.009406906043463116,-0.03652562332773208,-0.0017303366409506242

+0.540374,-0.01299278624355793,-0.056950896978378296,0.0022579410579055548,-0.009784304151328105,-0.03644892435257472,-0.0018579555583752897

+0.5481827,-0.012954920530319214,-0.056969162076711655,0.0022774594835937023,-0.009361792104324383,-0.036518861678702615,-0.0017561519856665775

+0.5579418,-0.012986435554921627,-0.05699574947357178,0.0022604113910347223,-0.009736183823566879,-0.036460123716564055,-0.001856489366632105

+0.5667256,-0.012948804534971714,-0.05701536312699318,0.002281749155372381,-0.009378199135548342,-0.036546008609549215,-0.0016908087661852247

+0.5803945,-0.01296931691467762,-0.05698087438941002,0.0023144965525716543,-0.009407371763539446,-0.036564038723240086,-0.0017048236356243896

+0.5862517,-0.012929723598062992,-0.05700203403830528,0.002339288592338562,-0.009393285245699878,-0.036540569309543226,-0.001721950110393556

+0.6008858,-0.013017875142395496,-0.0569298230111599,0.0022718843538314104,-0.009509087329696124,-0.0366019422746352,-0.0017304052824011118

+0.6086944,-0.0129275256767869,-0.056652944535017014,0.002326684072613716,-0.00951476979608464,-0.03659645665376411,-0.00173511126390713

+0.6204049,-0.01305336132645607,-0.05696631968021393,0.0022967590484768152,-0.00952858231011816,-0.036618566501683,-0.0017339422250181933

+0.6282187,-0.012919722124934196,-0.05668949335813522,0.002312298631295562,-0.009510442183601656,-0.03659417013085632,-0.0017484601789747479

+0.6409042,-0.013053907081484795,-0.05698978155851364,0.002269210061058402,-0.009499450944491339,-0.03666338853607275,-0.0017458497875941167

+0.6487109,-0.012962534092366695,-0.056717414408922195,0.0023250507656484842,-0.009499450944491339,-0.03666338853607275,-0.0017458497875941167

+0.6594458,-0.013094057328999043,-0.0569525845348835,0.0022552604787051678,-0.009485196252826655,-0.03665031429190763,-0.0017825525150895938

+0.6682359,-0.0130083616822958,-0.05667191371321678,0.0023163079749792814,-0.009485196252826655,-0.03665031429190763,-0.0017825525150895938

+0.6799423,-0.013090718537569046,-0.056952737271785736,0.002320796251296997,-0.009442407162080066,-0.03663404331506676,-0.0017691084163076935

+0.6877504,-0.012952952645719051,-0.05666309595108032,0.0023325111251324415,-0.009442407162080066,-0.03663404331506676,-0.0017691084163076935

+0.6994902,-0.013034988194704056,-0.05695563182234764,0.0023434609174728394,-0.00941422878715881,-0.03658501065008069,-0.0017513359513278027

+0.7092216,-0.012920527718961239,-0.056696996092796326,0.002366117900237441,-0.00941422878715881,-0.03658501065008069,-0.0017513359513278027

+0.718984,-0.013060931116342545,-0.056922104209661484,0.002294021425768733,-0.009841278709832094,-0.03655755086126383,-0.0018763137125136253

+0.7287419,-0.01292799785733223,-0.05666867271065712,0.0022911508567631245,-0.009438967853184606,-0.03664758872709846,-0.0017756496675178407

+0.740487,-0.013052650727331638,-0.05691701918840408,0.0022434103302657604,-0.009848597245386118,-0.03657592382716382,-0.0018883161046109743

+0.748285,-0.012932772748172283,-0.056661441922187805,0.0022541868966072798,-0.009478259736500625,-0.036655328998202355,-0.001781315115931397

+0.7589976,-0.013032927177846432,-0.05691377446055412,0.002224777825176716,-0.009908350356954575,-0.036552915046816535,-0.001878739885738936

+0.7687631,-0.012900101952254772,-0.056580837815999985,0.002247623633593321,-0.009550312512329918,-0.03660798431078569,-0.001789532312694307

+0.7804689,-0.012996920384466648,-0.05688949674367905,0.0022346677724272013,-0.009527757565242307,-0.03651283466477736,-0.001887108387213861

+0.7873017,-0.012996920384466648,-0.05688949674367905,0.0022346677724272013,-0.009527757565242307,-0.03651283466477736,-0.001887108387213861

+0.8009676,-0.013049381785094738,-0.05691670626401901,0.002227748977020383,-0.009489187457663958,-0.03656414834870699,-0.001879326311130681

+0.8078115,-0.013011015951633453,-0.056934621185064316,0.0022489482071250677,-0.00950348020815779,-0.03650031548393134,-0.0018603803572691804

+0.8185361,-0.013003945350646973,-0.05689042806625366,0.002276367973536253,-0.009399082293295781,-0.03651173641757764,-0.0018784411721190402

+0.827318,-0.012961968779563904,-0.056909386068582535,0.002299186773598194,-0.00936948991228991,-0.03647796013056136,-0.0018691254334254465

+0.8400065,-0.012983467429876328,-0.056972384452819824,0.002322426298633218,-0.009281416173203345,-0.036478076631324075,-0.0018449227009120965

+0.8497686,-0.012824936769902706,-0.056708548218011856,0.002385977189987898,-0.009268458317124185,-0.03645443150242977,-0.0018652760887816117

+0.8595259,-0.012977534905076027,-0.0569431409239769,0.0023172737564891577,-0.009279940695232131,-0.036487731643173274,-0.0018779477479910088

+0.8683093,-0.01283438503742218,-0.05676709860563278,0.002369006397202611,-0.009274374408894509,-0.036464849352313866,-0.0019111307782112244

+0.8780693,-0.012973674573004246,-0.05696054920554161,0.002297512488439679,-0.009315211324117443,-0.03649004515144904,-0.0019060337561560912

+0.8878291,-0.012815004214644432,-0.05668753385543823,0.002365821972489357,-0.009309667931595786,-0.036464985505673765,-0.0018948119360481608

+0.8975901,-0.013016575947403908,-0.05695377290248871,0.002258365275338292,-0.009240466945902965,-0.036485976100845176,-0.00190000469288795

+0.9083271,-0.012841988354921341,-0.05671067535877228,0.0022952097933739424,-0.009235514998471356,-0.036473449437565336,-0.0018763335257150659

+0.9190625,-0.012998937629163265,-0.056953124701976776,0.00222612451761961,-0.009292160624241744,-0.03649600681083691,-0.0018920696225093452

+0.9288231,-0.012837395071983337,-0.056693267077207565,0.00226804381236434,-0.009294169794302724,-0.03648653711903721,-0.0018869201724034423

+0.9385816,-0.012992636300623417,-0.056944988667964935,0.0022046947851777077,-0.0093340913557347,-0.03647678284759516,-0.0018900983560718393

+0.9483419,-0.012880397029221058,-0.05662329122424126,0.0023071281611919403,-0.0093249552397776,-0.036440260522416106,-0.0018864078001454222

+0.9590874,-0.013026310130953789,-0.056941889226436615,0.002281646942719817,-0.009354585449489706,-0.03651405192088877,-0.0018854972681198023

+0.9688376,-0.012861315160989761,-0.05666390806436539,0.0023203305900096893,-0.009371139706833308,-0.036487989237801915,-0.0018979064771529877

+0.9785988,-0.013028951361775398,-0.05699371173977852,0.002274760976433754,-0.00937564790859142,-0.03652068901164203,-0.0018757086430990387

+0.9893348,-0.012841659598052502,-0.05668270215392113,0.002299503656104207,-0.009355580848891518,-0.03652710895189967,-0.001870516741983607

+1.0000698,-0.013004882261157036,-0.05699971318244934,0.002254216931760311,-0.009318051252634355,-0.03655313894893479,-0.0019091576918930898

+1.0078778,-0.012842623516917229,-0.05668432265520096,0.0023060226812958717,-0.009303626478886065,-0.036527691944310096,-0.0018885344420827596

+1.0186295,-0.013005312532186508,-0.05698905885219574,0.0022560907527804375,-0.009346446038754628,-0.03652681817252329,-0.0019240759807399375

+1.0283739,-0.012870477512478828,-0.056714463979005814,0.002324136905372143,-0.009345888970554217,-0.03651785309886733,-0.0019448599987968221

+1.04009,-0.013048859313130379,-0.05696955695748329,0.0022365825716406107,-0.009379652352526031,-0.036563994259246294,-0.0019384694148989411

+1.0469179,-0.013013888150453568,-0.05699825659394264,0.0022506550885736942,-0.009386831133364339,-0.03655333304542737,-0.0019359770586214575

+1.0576538,-0.013056207448244095,-0.05694450065493584,0.002292494522407651,-0.009451060616369402,-0.03659094771595788,-0.0019398498456553942

+1.0683896,-0.012935164384543896,-0.056683991104364395,0.0023833559826016426,-0.009462780190005094,-0.036563002039603186,-0.0019244593332579643

+1.0791373,-0.013057218864560127,-0.056896552443504333,0.002337644575163722,-0.00939760006534739,-0.036628901286790395,-0.0019442440159086673

+1.0898639,-0.012863623909652233,-0.05668993294239044,0.0023414678871631622,-0.009407013063461344,-0.0366186127522514,-0.0019341330795581732

+1.0986459,-0.013005263172090054,-0.05693370848894119,0.0022879212629050016,-0.009361825763925642,-0.03662921816138868,-0.0019322646187526704

+1.1084057,-0.012877130880951881,-0.05668451264500618,0.00236547295935452,-0.009347849587694758,-0.03658343107721942,-0.0019366992523067036

+1.1181656,-0.013016048818826675,-0.05692062899470329,0.0023113652132451534,-0.009255065960281071,-0.036646387363615855,-0.0019477944195688168

+1.1279303,-0.012873194180428982,-0.05663652718067169,0.0023826074320822954,-0.009267904419882525,-0.03663831225920126,-0.0019625738137901798

+1.1382786,-0.013028525747358799,-0.0568884015083313,0.002317883772775531,-0.009254721406131252,-0.036695490963744276,-0.0019934416398009304

+1.1480392,-0.01282789558172226,-0.056647635996341705,0.0023188183549791574,-0.009237109927080382,-0.036661662808101354,-0.001975037413918303

+1.1587768,-0.012984507717192173,-0.05691986903548241,0.0022613676264882088,-0.00921062449647626,-0.03665903564882355,-0.001974056560021217

+1.168534,-0.01285270880907774,-0.05668098106980324,0.002333321375772357,-0.009194752575229838,-0.03660759047227727,-0.0019901669326734955

+1.1782949,-0.013021033257246017,-0.05699380859732628,0.0022805153857916594,-0.009174654112677818,-0.03665640789893409,-0.001962751886953393

+1.1890305,-0.012842124328017235,-0.056635674089193344,0.002345370128750801,-0.009142151133283585,-0.03660570447792795,-0.001956743487839581

+1.1978193,-0.013032570481300354,-0.05697362869977951,0.0022801447194069624,-0.009087442337165305,-0.03662394852983442,-0.001997603204717797

+1.2075814,-0.012843077071011066,-0.056686487048864365,0.002307617338374257,-0.009081513624636172,-0.03661900818764481,-0.001991396326845073

+1.2183107,-0.013014508411288261,-0.0570053793489933,0.0022540083155035973,-0.009126568537244119,-0.03663889142831085,-0.0019937507808331146

+1.2280767,-0.012900481931865215,-0.05667752027511597,0.0023058562073856592,-0.009093194305120733,-0.036643719104664546,-0.0019556275640615077

+1.2384118,-0.01303409319370985,-0.05699780210852623,0.0022774997632950544,-0.009232681395996737,-0.03668370371014775,-0.0019595424046621387

+1.2481916,-0.012934219092130661,-0.056685347110033035,0.002331420546397567,-0.009233529967009078,-0.03665173261297684,-0.0019595835346154

+1.2589065,-0.013067832216620445,-0.05698191374540329,0.0022930067498236895,-0.009249537997062095,-0.03668465431515804,-0.0019574888310465266

+1.2686674,-0.01294500008225441,-0.05667514726519585,0.002323468215763569,-0.009246239486524529,-0.036655619312567944,-0.0019863289999167578

+1.2774512,-0.013075277209281921,-0.056985605508089066,0.002287977607920766,-0.009249082141301934,-0.03665986846449385,-0.001988514301441777

+1.2872108,-0.01304306834936142,-0.05701185017824173,0.0023131463676691055,-0.00923905439037246,-0.036627801872835195,-0.001996371098069117

+1.2969714,-0.01310262642800808,-0.056987401098012924,0.0023114322684705257,-0.009220819078971971,-0.03664860446564174,-0.0019973067764910554

+1.3077077,-0.013072890229523182,-0.057012829929590225,0.002337150275707245,-0.009220322778251553,-0.03665518150219812,-0.0019943752244742

+1.3184431,-0.01305381953716278,-0.05691559985280037,0.0023158167023211718,-0.009213288041168572,-0.036628107871914416,-0.0019936327662118205

+1.3263985,-0.013020225800573826,-0.05693519860506058,0.002341747283935547,-0.009223882972894603,-0.03662530843500433,-0.0019812949646344272

+1.3378381,-0.013033388182520866,-0.056907251477241516,0.002317525213584304,-0.00922188884392877,-0.03662312612228911,-0.0019945401089589356

+1.3465542,-0.012997194193303585,-0.056924257427453995,0.0023418739438056946,-0.00921817209742942,-0.03658245202074743,-0.0019744031151062392

+1.3563146,-0.013000432401895523,-0.05689939111471176,0.0022986314725130796,-0.009222389464528033,-0.03656525251535205,-0.0019979223904159787

+1.3660736,-0.012961585074663162,-0.05691321939229965,0.002321830717846751,-0.009235798255375237,-0.03654880792311427,-0.002008454421150312

+1.3768144,-0.01297670416533947,-0.056967414915561676,0.0023394913878291845,-0.009222623806718672,-0.03654517093481708,-0.001975743068663993

+1.3865699,-0.01293826475739479,-0.05698072537779808,0.0023649120703339577,-0.009207796279404566,-0.036546951519772115,-0.0019511219420766928

+1.3973106,-0.013011429458856583,-0.0569705069065094,0.0023100825492292643,-0.009290117523697308,-0.03655950071472065,-0.0019404200191564824

+1.4080477,-0.012891441583633423,-0.05666476488113403,0.0023419386707246304,-0.00925749629252617,-0.03653172791466233,-0.001970500594507456

+1.4168304,-0.013041307218372822,-0.056954607367515564,0.0023019295185804367,-0.009318324259024003,-0.036575424553890346,-0.001988841322731443

+1.428538,-0.012943999841809273,-0.056596774607896805,0.0023104073479771614,-0.009364400105513435,-0.03657022558013451,-0.0020171648274200696

+1.4373264,-0.013108016923069954,-0.05684811994433403,0.0023154818918555975,-0.009288920269622442,-0.036656083623537145,-0.00206589423355453

+1.4480575,-0.013107693754136562,-0.05659424141049385,0.0023160725831985474,-0.009391797423615202,-0.03672394876436955,-0.0020210118596577916

+1.4568433,-0.013292890973389149,-0.0567961111664772,0.002360633574426174,-0.009097139083621369,-0.03663998527449084,-0.0017449777715741654

+1.4675836,-0.013306095264852047,-0.05655020475387573,0.0023066902067512274,-0.009405867542448206,-0.036707634476493715,-0.0015049665947006576

+1.4773376,-0.01345771737396717,-0.05673382803797722,0.00245854863896966,-0.009601783095081591,-0.03626766484629703,-0.0008417861980802129

+1.4880797,-0.013432870618999004,-0.05651204288005829,0.002309486037120223,-0.009419166964508785,-0.03587359922751592,7.962891146750837e-06

+1.4968625,-0.0136107187718153,-0.056708890944719315,0.002508218865841627,-0.00957409048879532,-0.03518755867054977,0.00107545725201095

+1.508368,-0.013543875887989998,-0.056460727006196976,0.002275083912536502,-0.009953218167185793,-0.034700910722449504,0.0022341694997589276

+1.5169706,-0.013684959150850773,-0.056724198162555695,0.0025894036516547203,-0.010037950578718993,-0.033982459882019124,0.0031638842014376097

+1.5274897,-0.013600938022136688,-0.056436937302351,0.0022895371075719595,-0.010380654254780434,-0.03327400517824025,0.004018475025274539

+1.5362397,-0.013813883066177368,-0.05668111518025398,0.002570703625679016,-0.010951559438713277,-0.03217840188678549,0.005200944912006948

+1.5479842,-0.013753673061728477,-0.0564081035554409,0.0022446385119110346,-0.011260767331729647,-0.031836548546346696,0.006104277689123826

+1.5567781,-0.013898675329983234,-0.05665917322039604,0.0025875759311020374,-0.012066761528233653,-0.03068111704223981,0.007135180276063701

+1.5675029,-0.013846014626324177,-0.05639238655567169,0.0021879738196730614,-0.012361988127129566,-0.031044187227091007,0.007131741904089993

+1.5762564,-0.01396267581731081,-0.056690797209739685,0.002553593134507537,-0.01312380135115149,-0.03040879579997759,0.007011711893907712

+1.5880268,-0.013910445384681225,-0.05632675811648369,0.0021678635384887457,-0.013879212658339931,-0.030127725187814636,0.007345650208359165

+1.5967775,-0.014063840731978416,-0.056668803095817566,0.00256555899977684,-0.015319930059897499,-0.03017328378907078,0.007314919432393273

+1.6074868,-0.01400663610547781,-0.056293778121471405,0.0021619044709950686,-0.0169195528115031,-0.030589625011345434,0.007283267250794626

+1.6172471,-0.014150549657642841,-0.05660339072346687,0.002548063872382045,-0.017518907071620918,-0.030713729682165278,0.0068477657466120626

+1.6279848,-0.014163980260491371,-0.05621103197336197,0.0021563901100307703,-0.018351545870985444,-0.030848909820462005,0.006728214336710564

+1.6367664,-0.014298628084361553,-0.056531988084316254,0.0025601384695619345,-0.019173721131911296,-0.03051586849769655,0.0059791302423592135

+1.6460222,-0.01479863841086626,-0.05657578259706497,0.0025187439750880003,-0.019856853175556532,-0.03092608996009655,0.006072245889026443

+1.6569582,-0.014514905400574207,-0.05646810680627823,0.0026028435677289963,-0.0216591002079085,-0.030869043446445806,0.005803895998110338

+1.6676708,-0.015041347593069077,-0.05651603639125824,0.002598854713141918,-0.0235711462927308,-0.031323491522665885,0.0065360649396862015

+1.6774308,-0.01480929646641016,-0.05633457005023956,0.002764974720776081,-0.02626125875363735,-0.030286008170958497,0.008949618038141977

+1.6881663,-0.014888476580381393,-0.055997949093580246,0.002462920034304261,-0.028535808746408865,-0.02850912237676227,0.011904856812170158

+1.6969549,-0.01515629980713129,-0.05632699653506279,0.0029392021242529154,-0.031118074168871915,-0.026772192314936962,0.016319593423692415

+1.7096385,-0.015285691246390343,-0.05601002275943756,0.002674172166734934,-0.033665677780194664,-0.025398436600398196,0.020298981969508884

+1.7174466,-0.015558063983917236,-0.05636686831712723,0.003150023054331541,-0.03568144530165803,-0.022248233735172596,0.021801392450776603

+1.7281823,-0.015680618584156036,-0.055997151881456375,0.0028314823284745216,-0.03718443080050102,-0.022464528631058953,0.02126781949189947

+1.7418796,-0.016024023294448853,-0.05636075511574745,0.0031510228291153908,-0.03829141229717507,-0.022990457146053963,0.01917445063502594

+1.747703,-0.016124166548252106,-0.056026820093393326,0.002739287680014968,-0.03937379162914713,-0.02437470687642373,0.017829476786841627

+1.7574961,-0.016463028267025948,-0.056331343948841095,0.003033772809430957,-0.04080897488944248,-0.02418926459080236,0.01607061860052777

+1.7681979,-0.01663285493850708,-0.055981412529945374,0.0027321986854076385,-0.04258674798732987,-0.023452575841329995,0.015059730371328375

+1.7760066,-0.016986219212412834,-0.056416429579257965,0.003181043779477477,-0.04454037157078701,-0.023437084678520678,0.01643638891290535

+1.7877186,-0.01715855859220028,-0.05611289292573929,0.002987132640555501,-0.04621980001575357,-0.02276317524790048,0.01877953669172542

+1.7965026,-0.017536843195557594,-0.056538764387369156,0.003536813659593463,-0.04772090187568951,-0.020094422716133774,0.020332386032675828

+1.8091901,-0.017713729292154312,-0.05623001232743263,0.0034800791181623936,-0.04901905377233028,-0.01708675882770374,0.022066248521318083

+1.8160228,-0.01814630813896656,-0.056639935821294785,0.004125906620174646,-0.0503481444202934,-0.013237585300507781,0.023437132625863822

+1.8267577,-0.018319515511393547,-0.05629437789320946,0.004234745167195797,-0.05149357207979364,-0.009353475791286394,0.02307318771006782

+1.8355425,-0.018778664991259575,-0.056737832725048065,0.005098204128444195,-0.052570943568811666,-0.0027090836027674455,0.01933935322399474

+1.847807,-0.018883634358644485,-0.05636486038565636,0.005313620902597904,-0.05318389964729022,0.0045473113028288124,0.014575798787387951

+1.8565919,-0.01924487203359604,-0.05675193667411804,0.006264036521315575,-0.05347239619289073,0.01154016290118192,0.00890373830598057

+1.8673279,-0.0194260086864233,-0.05642719194293022,0.00678412988781929,-0.05361886489679559,0.01720006411886019,0.003836150601711163

+1.8761112,-0.01981792412698269,-0.05676266923546791,0.007863514125347137,-0.05385958737736349,0.022892234936072973,-0.0005082521407082228

+1.8878293,-0.019970908761024475,-0.05652208998799324,0.00864390004426241,-0.05395947807081612,0.02800337415877962,-0.0033500824740986678

+1.8956312,-0.020244160667061806,-0.05681410804390907,0.010007843375205994,-0.05406795820259372,0.03289862933464659,-0.005058389085878873

+1.9054993,-0.02068213000893593,-0.057051461189985275,0.01126271951943636,-0.05414225767541079,0.036145906409815576,-0.005642945057844729

+1.9162353,-0.02057589776813984,-0.05689426138997078,0.012507258914411068,-0.05432650055532503,0.03826573138374267,-0.005512416700446896

+1.9260274,-0.02091263234615326,-0.057108134031295776,0.013935696333646774,-0.05443370635855864,0.03910093958694936,-0.0044729159829361

+1.9367865,-0.02087038941681385,-0.056944385170936584,0.015556225553154945,-0.05458459783787874,0.03884498897292077,-0.002436880268199902

+1.9471992,-0.020906375721096992,-0.05671488121151924,0.017168089747428894,-0.054336834561151424,0.03815177567898046,-0.00015377266612514264

+1.956941,-0.021057311445474625,-0.05696515738964081,0.019046826288104057,-0.05399608506208083,0.037225708706778986,0.0010052670831832257

+1.967672,-0.02109294757246971,-0.056627221405506134,0.02108684368431568,-0.05381518288770623,0.03628474370235758,0.0016422111443149367

+1.9754792,-0.02118026651442051,-0.05686361715197563,0.023300539702177048,-0.053753255131943393,0.034401981265420455,0.0015309696148093905

+1.9881705,-0.021185802295804024,-0.05661090090870857,0.025759823620319366,-0.053389780977187315,0.031388217859525655,7.617871763360898e-05

+1.9969537,-0.021136606112122536,-0.05673997476696968,0.028373122215270996,-0.05310910863221458,0.028175854497549193,-0.0033050432514536983

+2.0076873,-0.021194027736783028,-0.05638407543301582,0.03139358386397362,-0.05257404366651876,0.024936193492111965,-0.007720145949604086

+2.0154949,-0.021120356395840645,-0.056374259293079376,0.034357983618974686,-0.052101982743676105,0.022686935360208948,-0.012754644350338976

+2.0272077,-0.02110697515308857,-0.0559704452753067,0.037810344249010086,-0.05133300295862735,0.022117595858521452,-0.017186606512004182

+2.0359904,-0.020969878882169724,-0.055935826152563095,0.04124915972352028,-0.050866813130792776,0.02318776645769744,-0.02057073436128206

+2.0473637,-0.020925167948007584,-0.055463142693042755,0.04517900198698044,-0.05021319238507649,0.025253089973657907,-0.022214525005673922

+2.0561147,-0.020791593939065933,-0.055305324494838715,0.04898904636502266,-0.049475057955636295,0.027419778177187618,-0.022509688051215924

+2.0668502,-0.020727740600705147,-0.05482116714119911,0.05341015383601189,-0.048684462918301065,0.028328107591423374,-0.020317524343791957

+2.0766102,-0.020563513040542603,-0.05463857203722,0.05768937990069389,-0.048175781231357406,0.027373498041606333,-0.01664347604019154

+2.0863704,-0.020528823137283325,-0.05401788651943207,0.06270197033882141,-0.04752748824452725,0.024970649793544412,-0.012576345662950704

+2.0961314,-0.02038772590458393,-0.053746309131383896,0.06736550480127335,-0.047174617385127696,0.021551936524619782,-0.009066959494722582

+2.1068791,-0.020273614674806595,-0.0531260147690773,0.07278561592102051,-0.046783593972384775,0.018758703809343906,-0.0062707907614273275

+2.115651,-0.020149338990449905,-0.052754420787096024,0.07780390977859497,-0.04646443987094212,0.015870611426043648,-0.004720345769100959

+2.1273627,-0.02004595473408699,-0.05212957784533501,0.08367065340280533,-0.04617949103530051,0.013896999673716269,-0.003067527770619324

+2.1351703,-0.019914541393518448,-0.051764898002147675,0.089130699634552,-0.04581588784927164,0.012446070997460696,-0.0018550063299380486

+2.1468824,-0.01980314403772354,-0.05101485922932625,0.09548453241586685,-0.045846433560540016,0.01200898370434573,-0.00036163136554749484

+2.1566439,-0.019673079252243042,-0.05062102526426315,0.10136239230632782,-0.04614023083118143,0.011532630347544523,0.0008305303052761881

+2.1673792,-0.01956927962601185,-0.04986371472477913,0.10810708999633789,-0.04646761801108203,0.011165422925791845,0.0023099526392287534

+2.1761637,-0.019443508237600327,-0.04946531727910042,0.11434918642044067,-0.04627685159493638,0.009991410535677332,0.003683966173430001

+2.1888883,-0.01937260664999485,-0.048678312450647354,0.12151571363210678,-0.04650108829669828,0.009174732181798338,0.00540319647166096

+2.1957204,-0.019317515194416046,-0.04824484512209892,0.1280617117881775,-0.04611069901853315,0.007940324917304675,0.007449893351773539

+2.2074339,-0.019273698329925537,-0.04742121696472168,0.1356411576271057,-0.04624441708889855,0.00697475737949147,0.009141187046875488

+2.2162216,-0.01928325556218624,-0.04706939309835434,0.1425386369228363,-0.046243224786864975,0.005454448944157022,0.010376091833510476

+2.2279286,-0.01919667050242424,-0.0462578609585762,0.15040285885334015,-0.046137180258199656,0.003911912583100494,0.01169755966545021

+2.2348813,-0.018890123814344406,-0.04596744477748871,0.15804915130138397,-0.046068898374274844,0.002228071318972353,0.012786194296184527

+2.2466079,-0.018955327570438385,-0.045557476580142975,0.16537660360336304,-0.04574485254233774,0.00048197248172387775,0.01440967945222283

+2.2553495,-0.018665673211216927,-0.04529271274805069,0.1733250617980957,-0.045544227315435726,-0.00048460087508221433,0.01649536684778567

+2.2641327,-0.018626226112246513,-0.04488896206021309,0.18097063899040222,-0.04518045918509522,-0.0006768266422598096,0.019066015494567597

+2.2778026,-0.018562553450465202,-0.044572342187166214,0.18873126804828644,-0.044783461913155534,5.578942200844087e-05,0.02166827652392109

+2.2867171,-0.018312474712729454,-0.04435517266392708,0.19694745540618896,-0.043962416021094436,0.0015152490810417347,0.02396944748886089

+2.2965572,-0.018062638118863106,-0.04416229948401451,0.20523914694786072,-0.043308719962874005,0.0037344944919236508,0.025440699612076116

+2.305211,-0.01799280010163784,-0.04388102516531944,0.21317413449287415,-0.04205807962863521,0.005568414966793411,0.026025556649093916

+2.3178985,-0.017919868230819702,-0.04366462305188179,0.22116529941558838,-0.041173200096131415,0.007325350216734659,0.025719003587572266

+2.3266829,-0.017695540562272072,-0.043535016477108,0.22957052290439606,-0.039785888612141315,0.008314728224246453,0.02433669268211776

+2.3374182,-0.01757541112601757,-0.043367013335227966,0.23770180344581604,-0.03893017886243522,0.009203346782451343,0.022123231606915494

+2.3452901,-0.017349116504192352,-0.04327881708741188,0.24614791572093964,-0.037790903334803276,0.009794107924556752,0.019738630583326217

+2.3579164,-0.017215097323060036,-0.043172337114810944,0.25428497791290283,-0.037153622440880295,0.010557072965561737,0.017958434451498858

+2.3666984,-0.016982821747660637,-0.04311865195631981,0.26269838213920593,-0.036281738388380676,0.011443721332351728,0.01751470964579285

+2.3754826,-0.016740618273615837,-0.04308249428868294,0.2710990309715271,-0.035901113332255125,0.012348364350984497,0.018289165854406098

+2.3855818,-0.016487611457705498,-0.0430639386177063,0.27947998046875,-0.035592011357525676,0.012838994300945138,0.019512432182058902

+2.3961952,-0.01622338779270649,-0.04306356981396675,0.2878226935863495,-0.03540221419241582,0.013005203880329743,0.02029494541301018

+2.4069272,-0.019099632278084755,-0.039298057556152344,0.2990075349807739,-0.03538957761540461,0.013034933201082167,0.02038525786003608

+2.4157159,-0.018954651430249214,-0.03909262269735336,0.30739742517471313,-0.03579852969577164,0.010857866884860169,0.01677290515058192

+2.4284002,-0.018973659723997116,-0.038433339446783066,0.31601592898368835,-0.03649582433021786,0.01008722128609995,0.015007742995582676

+2.4342599,-0.018815308809280396,-0.03822512924671173,0.32426396012306213,-0.03668186186278299,0.009106435563307305,0.013401685660999425

+2.446948,-0.018768364563584328,-0.03794964775443077,0.3326064646244049,-0.03718815747180162,0.008145930381042957,0.012156226887502843

+2.455728,-0.018602434545755386,-0.0377618782222271,0.3406834602355957,-0.03715635562671236,0.007540951130907903,0.011585737294211163

+2.467444,-0.018522176891565323,-0.03768368437886238,0.348753422498703,-0.0374486846331225,0.007199646315752867,0.012096368795711526

+2.4752472,-0.01835230365395546,-0.03752622380852699,0.35662662982940674,-0.03719781739393255,0.007576503519654494,0.013152624934017717

+2.4879399,-0.018276380375027657,-0.03754633292555809,0.36442887783050537,-0.03705222708021502,0.008096446994436098,0.014871045018053884

+2.495748,-0.01810459978878498,-0.03742833808064461,0.3720746338367462,-0.03651354542897135,0.008863723269937406,0.016248754140670226

+2.5074584,-0.018040228635072708,-0.03752205893397331,0.37958258390426636,-0.03639259285345687,0.009813564702198721,0.01768169103392079

+2.5152626,-0.017866095528006554,-0.037452343851327896,0.38695135712623596,-0.03575328948083671,0.011150325173797056,0.018264341170408833

+2.5279905,-0.017798559740185738,-0.03758639842271805,0.3941405415534973,-0.03562481587575661,0.012336299866811715,0.018454370184257007

+2.5377112,-0.021615294739603996,-0.03687158599495888,0.3985566198825836,-0.034828981232806804,0.013342740098512593,0.01727147209197007

+2.5484496,-0.021619947627186775,-0.03629601374268532,0.4053385555744171,-0.034018292395192794,0.010987381151680934,0.01563462145079639

+2.5582128,-0.02236018516123295,-0.03790387883782387,0.41146716475486755,-0.033223638286744656,0.011164577280759369,0.012935130413437404

+2.5679706,-0.022376714274287224,-0.03639724478125572,0.4179464280605316,-0.03237471363628026,0.01037652609046525,0.010297052236959252

+2.5778153,-0.023028604686260223,-0.03817448019981384,0.42387115955352783,-0.03089083390703923,0.009717677788821226,0.00829339287997908

+2.5855705,-0.02290261909365654,-0.03636591508984566,0.43000856041908264,-0.03023177339787938,0.009816739663171552,0.00660675098196233

+2.5982246,-0.023583199828863144,-0.038291215896606445,0.4357081651687622,-0.029738042538552643,0.009960673153518574,0.006002299201927426

+2.6080213,-0.02336770109832287,-0.036321960389614105,0.44143763184547424,-0.02977648157610894,0.010986803172185904,0.0057512308156857156

+2.6177435,-0.024020517244935036,-0.038445569574832916,0.4469327926635742,-0.028043913859833656,0.011941963495715156,0.007270726250574449

+2.6265311,-0.023739652708172798,-0.03635908663272858,0.45228809118270874,-0.027378335473378864,0.013367264886300667,0.00855250630602899

+2.6372631,-0.024389075115323067,-0.03854408860206604,0.45749524235725403,-0.02709199092554905,0.015199482345939255,0.009245213079285042

+2.6480563,-0.024112015962600708,-0.03638207167387009,0.4625800848007202,-0.026465990935343922,0.016615098415139622,0.010126093741845628

+2.656877,-0.024745367467403412,-0.03870883956551552,0.4675404727458954,-0.025961191362208542,0.017991828506409586,0.010202120936356463

+2.6685538,-0.024410473182797432,-0.03655426949262619,0.4722728729248047,-0.025242341425043502,0.018907976117457714,0.009639321057974704

+2.6783136,-0.025003667920827866,-0.03893846645951271,0.47700580954551697,-0.024848902564364384,0.019571638536822925,0.008710590416304105

+2.6890518,-0.024566849693655968,-0.036745984107255936,0.4813570976257324,-0.02435725420225339,0.01956808191094873,0.007524287615568987

+2.6978369,-0.025124993175268173,-0.03922828286886215,0.485880047082901,-0.02391592920905674,0.019567539861649837,0.006445951391102377

+2.7085698,-0.02463785745203495,-0.037038400769233704,0.4899318814277649,-0.02332168623757054,0.01958142383520847,0.00572137212098433

+2.7183283,-0.025133932009339333,-0.03960093483328819,0.4942801892757416,-0.02167824969192471,0.019176241864731294,0.006133991353568171

+2.7271215,-0.024591535329818726,-0.03736921399831772,0.49806514382362366,-0.02211194326359167,0.01980765309172202,0.005316121306205974

+2.7378709,-0.025072738528251648,-0.039959557354450226,0.5021786689758301,-0.020669925018950125,0.019372854293081783,0.00647889070279855

+2.7476128,-0.02447420172393322,-0.03769088536500931,0.5057070255279541,-0.0210313557402164,0.020025495337863186,0.0059030221681269065

+2.7583444,-0.024921387434005737,-0.040388260036706924,0.5096480846405029,-0.020308896217662423,0.019809028250961324,0.007180795528357243

+2.7681042,-0.024202991276979446,-0.03817816823720932,0.5131872296333313,-0.020879565394929238,0.020633260757299744,0.006289308455059699

+2.7768933,-0.02467154711484909,-0.04085952416062355,0.5167750716209412,-0.020055580770634927,0.020298492773281995,0.0073571529169623034

+2.7876288,-0.024022454395890236,-0.03855215013027191,0.5198560357093811,-0.020624666589268235,0.0209775880303214,0.005978885349315177

+2.7973888,-0.02439759485423565,-0.04126449674367905,0.523341953754425,-0.019894003149407435,0.02044357044703835,0.006600187305076824

+2.8071493,-0.02374936453998089,-0.038989752531051636,0.5262827277183533,-0.02040829812572118,0.02090757384941047,0.0050601928111558715

+2.8179557,-0.024075759574770927,-0.04180988296866417,0.5296661257743835,-0.019358614362874827,0.020102815691061426,0.0059874791645936

+2.825693,-0.02337834984064102,-0.03942720219492912,0.5324392318725586,-0.0191123598387214,0.01962962969728887,0.005562431828822853

+2.8375033,-0.02369830757379532,-0.04230881482362747,0.535650908946991,-0.018730151126573898,0.018992464818278546,0.005475305126587226

+2.8461843,-0.022969545796513557,-0.03989394009113312,0.5382797122001648,-0.019001398941940147,0.018835235929778704,0.004217287991199658

+2.8559446,-0.023210076615214348,-0.042781420052051544,0.541415274143219,-0.018830710542336464,0.01796546528620064,0.004319209380814199

+2.8676609,-0.022467656061053276,-0.04041633382439613,0.5438968539237976,-0.01860259402798751,0.01715883503232668,0.004326407351685969

+2.8774915,-0.022658571600914,-0.043346550315618515,0.546911895275116,-0.018516057342909186,0.01646068944324691,0.004444222571569967

+2.8862049,-0.021904703229665756,-0.0409122109413147,0.549298882484436,-0.017600769967774904,0.015157862915466372,0.005843990745609085

+2.8979123,-0.022099267691373825,-0.04387285187840462,0.5521466732025146,-0.017187357957908336,0.014643014144139873,0.005662749823252054

+2.9057208,-0.021354688331484795,-0.04141584411263466,0.5544597506523132,-0.017026686660029173,0.014195680949622215,0.005178063527096047

+2.9174374,-0.02150699496269226,-0.04441981390118599,0.5572576522827148,-0.016530253984872498,0.013554754461822992,0.004798178685381424

+2.9271925,-0.02070792391896248,-0.04196694865822792,0.5594315528869629,-0.017075199925012698,0.013353796173571804,0.0029054452497953727

+2.9369528,-0.020825570449233055,-0.045016348361968994,0.562171220779419,-0.016106529201215813,0.011989645845878234,0.003913995327681384

+2.9477403,-0.020016098394989967,-0.04257397726178169,0.5642645955085754,-0.016726375294878144,0.011689355659306802,0.0019702809553618778

+2.9546543,-0.019616207107901573,-0.04278486222028732,0.5666866302490234,-0.01667267147352943,0.01072354667873755,0.0016119675366549164

+2.967216,-0.018905822187662125,-0.0419924259185791,0.5687770247459412,-0.017363279111216316,0.010071475225348195,0.00040180110681793186

+2.9779443,-0.019125254824757576,-0.04548639431595802,0.5713523626327515,-0.016497779443846276,0.008001873959979495,0.002149413340446154

+2.9877748,-0.01841227151453495,-0.04345624893903732,0.57333904504776,-0.01703899139309003,0.0074893389492829004,0.00021207685317436311

+2.9974644,-0.01848222315311432,-0.04657597467303276,0.5757758617401123,-0.01604315350010632,0.00580974407628941,0.0018776753360194593

+3.0082211,-0.017771217972040176,-0.04413263127207756,0.577781081199646,-0.016765979967851403,0.005588155014720648,0.0004961346904274467

+3.0160123,-0.017877809703350067,-0.04714232310652733,0.5800841450691223,-0.01579286344085142,0.004398590067750514,0.0022224217589748544

+3.0267488,-0.017124183475971222,-0.04467111453413963,0.5819833874702454,-0.016500038727478544,0.004435111704394822,0.0008337781366467284

+3.037485,-0.01724323444068432,-0.04764549434185028,0.5842434763908386,-0.015444164082868719,0.0030339652204570914,0.0023916867455199106

+3.0472451,-0.01644168607890606,-0.045066915452480316,0.5860244035720825,-0.016358006271975107,0.0028899759253469275,0.0007889858076787572

+3.0571078,-0.01656172424554825,-0.0480649508535862,0.5882773995399475,-0.015519282713963405,0.0017839197968091262,0.0018938935240919547

+3.0678391,-0.015782533213496208,-0.04547853395342827,0.5900568962097168,-0.01637572371337055,0.0018035203056824618,-0.0002059972437482943

+3.0766231,-0.015943504869937897,-0.04849667474627495,0.5922222137451172,-0.015526330117710723,0.00045201127884902996,0.0005442952542329322

+3.0873637,-0.015032919123768806,-0.04594171419739723,0.5939998626708984,-0.016047892251300735,0.0004628517992381425,-0.002053626765837329

+3.0961596,-0.015188455581665039,-0.048957038670778275,0.5960808992385864,-0.015133406224273912,-0.0009403401910492169,-0.001026479328872555

+3.1078552,-0.014401557855308056,-0.0463276170194149,0.5976704359054565,-0.015721077225826323,-0.001026814191591668,-0.0030773664011413335

+3.1166436,-0.01454984862357378,-0.04938698932528496,0.5997501611709595,-0.014949748914876316,-0.002310539952352717,-0.0015758426757233046

+3.1264036,-0.01373488549143076,-0.0467708557844162,0.6012122631072998,-0.015727631968122838,-0.002367716325648966,-0.0031251979047629197

+3.1351875,-0.01392147783190012,-0.04980352148413658,0.6032156944274902,-0.015063451528844234,-0.0037952473538943477,-0.0010837442146623246

+3.1459193,-0.013132588937878609,-0.047122567892074585,0.6046708822250366,-0.015116441387204138,-0.004095265033225642,-0.0006478792121500569

+3.1547038,-0.012763959355652332,-0.047308508306741714,0.6065791845321655,-0.015771948004982245,-0.0038078564963883433,-0.0019598849859743485

+3.1664152,-0.012051880359649658,-0.04636120796203613,0.6079703569412231,-0.01572993435788432,-0.0041932425472551525,-0.0017456257077324163

+3.1751996,-0.011658805422484875,-0.046467024832963943,0.6097702980041504,-0.016532177333875617,-0.004194035276581134,-0.0029485988303874456

+3.1878871,-0.011085329577326775,-0.046279747039079666,0.6111644506454468,-0.017045330299622154,-0.004357473274753872,-0.0035882653076028713

+3.1947237,-0.010683414526283741,-0.04635164886713028,0.6128793954849243,-0.01692353808105362,-0.004848616014207311,-0.003611319317195243

+3.2083833,-0.010206261649727821,-0.046438541263341904,0.6142904758453369,-0.01741369227855616,-0.0055054172575942206,-0.003398590636943075

+3.214239,-0.009806836023926735,-0.04650270938873291,0.6159552335739136,-0.017242039962043383,-0.00599792387286796,-0.002916544384436095

+3.2270162,-0.009418439120054245,-0.04672837257385254,0.6173650622367859,-0.01804032506039315,-0.006348999767669068,-0.0018898290901480854

+3.2347351,-0.009031292982399464,-0.04680827632546425,0.618986189365387,-0.01805672949568561,-0.006518210449081778,-0.0009897021474522276

+3.2474249,-0.008700395934283733,-0.0471125990152359,0.6202842593193054,-0.018760137523538833,-0.006940479464806663,0.00032342706299621696

+3.2562072,-0.010397530160844326,-0.04921971261501312,0.6214922666549683,-0.017563204153964444,-0.009632121589970783,0.005538538924129743

+3.2669431,-0.009734075516462326,-0.04861997812986374,0.622527003288269,-0.01817434978011663,-0.009377725593019784,0.005177897312780849

+3.2747513,-0.009499535895884037,-0.04896164312958717,0.6239851713180542,-0.018043459927156412,-0.009954612067966743,0.00589924754907596

+3.2874399,-0.008953914046287537,-0.048653606325387955,0.6251062750816345,-0.01857678361960799,-0.010078539652846111,0.005272270222777114

+3.2942716,-0.008710270747542381,-0.04894682392477989,0.6265040636062622,-0.018458206962054118,-0.010423890044519872,0.004843202127633932

+3.3079356,-0.008219270035624504,-0.04891418293118477,0.62762451171875,-0.01914979810417656,-0.01024359292071139,0.003211420689347599

+3.3167192,-0.009397214278578758,-0.05105944350361824,0.628907322883606,-0.018146715814028554,-0.01204983307484046,0.004661266886818194

+3.3264783,-0.008875777013599873,-0.05004050210118294,0.6297820210456848,-0.019038603577135025,-0.011324947293495213,0.0018929122062048681

+3.3352629,-0.00872749648988247,-0.050416212528944016,0.6310795545578003,-0.018872921031609133,-0.011114761796904803,0.0005282141125323815

+3.3475423,-0.008296158164739609,-0.049853306263685226,0.6320806741714478,-0.01922059660147561,-0.010489178114811152,-0.0014797094368945005

+3.3572712,-0.00918171089142561,-0.05238063260912895,0.6333730220794678,-0.017529270118993436,-0.011811546314629544,-0.00017961539974015154

+3.3670289,-0.008733558468520641,-0.05082406848669052,0.6341896653175354,-0.018306923224552442,-0.010666582922529729,-0.0017177815247642486

+3.3748117,-0.008645622059702873,-0.05118127167224884,0.6353563070297241,-0.018157162343065955,-0.010420600091762646,-0.001709044752744264

+3.3865236,-0.008268645033240318,-0.050390440970659256,0.6361595988273621,-0.018789128422822717,-0.009689550480684714,-0.0027835634571688733

+3.3943314,-0.008167288266122341,-0.05068284645676613,0.6372490525245667,-0.018649292208880026,-0.009347757211184301,-0.0031114453011819045

+3.4079952,-0.00783077348023653,-0.050367437303066254,0.6381314992904663,-0.019439223628221928,-0.00861741745342716,-0.004296751604239098

+3.4148318,-0.007720737252384424,-0.05060671642422676,0.6391918063163757,-0.019280776547200944,-0.008127832222167453,-0.004798817145504121

+3.4275364,-0.00739467004314065,-0.050539884716272354,0.6400496363639832,-0.019753168021526737,-0.007362634747005322,-0.0058740114138630985

+3.4343473,-0.00727783003821969,-0.050734806805849075,0.6410951614379883,-0.019570781498789495,-0.00705491086750271,-0.006441677208132163

+3.4470397,-0.007044946309179068,-0.05079187825322151,0.6420751810073853,-0.02008458183434154,-0.006514984727681156,-0.006854142036261003

+3.4548429,-0.006930005736649036,-0.05095595493912697,0.6431372165679932,-0.01991365985799498,-0.006080635189706964,-0.006578911496304357

+3.4665549,-0.00675021531060338,-0.05105907469987869,0.6441556215286255,-0.020137533710342766,-0.005853512072412761,-0.006021984648536234

+3.4743628,-0.006640822626650333,-0.051201898604631424,0.6452221274375916,-0.01985818296263849,-0.005925165226202872,-0.005122523971249058

+3.4880278,-0.00648404099047184,-0.05133374407887459,0.6461735963821411,-0.020052117450986683,-0.006140456533428203,-0.004161814873764357

+3.4948594,-0.006381701678037643,-0.05146439000964165,0.6472099423408508,-0.01970461976994179,-0.0065886231844721095,-0.0032299049449340026

+3.5075481,-0.006270550657063723,-0.05163150653243065,0.6481507420539856,-0.0199162323491243,-0.006881705351133418,-0.0021577286630429164

+3.5143797,-0.006179943680763245,-0.05175967514514923,0.649150550365448,-0.019616138413280637,-0.0074141475910218385,-0.0015956231697692265

+3.5270675,-0.006105147767812014,-0.05196414142847061,0.6500049829483032,-0.019804618619377847,-0.007659220140112615,-0.001152433409963678

+3.53488,-0.006029866635799408,-0.0520973838865757,0.6509586572647095,-0.019450543059421,-0.0076137491588017265,-0.0011287172356275721

+3.5465875,-0.00597583781927824,-0.05229268595576286,0.651883602142334,-0.019744000539839584,-0.007367279067995103,-0.0012244548464204813

+3.5535441,-0.005917295813560486,-0.0524299256503582,0.6528233289718628,-0.01939311449201369,-0.0069011270927296356,-0.0015185473215457348

+3.5662326,-0.005895698443055153,-0.05264604464173317,0.6537270545959473,-0.01941759615773179,-0.006850281412479205,-0.0017069023375722693

+3.5750168,-0.00585433142259717,-0.05278855562210083,0.6546818614006042,-0.0189106372189356,-0.006878492303124552,-0.001873298722448441

+3.5867332,-0.005848684348165989,-0.05301806703209877,0.655639111995697,-0.019333124085213246,-0.007316269894376306,-0.0017425264151491944

+3.5945412,-0.005824903957545757,-0.053165752440690994,0.6566303968429565,-0.01906221050090238,-0.00732335813601187,-0.0015793032340401388

+3.6082008,-0.005809985566884279,-0.05338184908032417,0.6575815677642822,-0.01932075759849418,-0.007227812906859092,-0.001208549089489193

+3.6140566,-0.005801948253065348,-0.05353275313973427,0.6585515141487122,-0.018921236591278763,-0.00714318811658249,-0.000903978617270004

+3.6267493,-0.00579365948215127,-0.05376237630844116,0.6594886183738708,-0.018980211942512714,-0.007054398844960401,-0.0005616145942323907

+3.6345572,-0.005801023915410042,-0.053918227553367615,0.6604525446891785,-0.018602635718277843,-0.006935885030049102,-0.0004207523772067289

+3.6482192,-0.005783990025520325,-0.0541536808013916,0.6613480448722839,-0.018596796484063798,-0.006657934104906518,-0.00020556767364194364

+3.6540771,-0.0058046625927090645,-0.054314885288476944,0.6623110175132751,-0.01829446058218724,-0.006467804662958299,-0.00046423034109203

+3.667741,-0.005798922386020422,-0.05458768457174301,0.6632141470909119,-0.01875445398531726,-0.006265009040377338,-0.0007057633153626557

+3.6745735,-0.005832965020090342,-0.05475679785013199,0.6641536355018616,-0.018404463468038496,-0.006147207357715206,-0.0011870376100807352

+3.687261,-0.005829912144690752,-0.05504043027758598,0.66508948802948,-0.01862105219884069,-0.006027270830755503,-0.0014371739391076967

+3.6940925,-0.0058759115636348724,-0.055214475840330124,0.6659960150718689,-0.018201385349630582,-0.005988992527170275,-0.0015885891573791907

+3.7077578,-0.005984700750559568,-0.05548037588596344,0.6671425104141235,-0.01798563715102031,-0.005871665784177384,-0.00159101576529626

+3.7145848,-0.011213078163564205,-0.0550348199903965,0.6663829684257507,-0.015942131198756804,-0.009347184818823689,0.0008128752438073103

+3.7262968,-0.011284658685326576,-0.05473634973168373,0.667109489440918,-0.015685142411418072,-0.00833245096036486,-0.00018557439892305364

+3.7350852,-0.01158627588301897,-0.054970044642686844,0.6679646372795105,-0.015685142411418072,-0.00833245096036486,-0.00018557439892305364

+3.7467926,-0.01159291248768568,-0.05464691296219826,0.6686460971832275,-0.015888121163954407,-0.006932616482863673,-0.001583613527020864

+3.7546052,-0.01159291248768568,-0.05464691296219826,0.6686460971832275,-0.015888121163954407,-0.006932616482863673,-0.001583613527020864

+3.7672931,-0.011851519346237183,-0.05451136454939842,0.6701127290725708,-0.01606789691763179,-0.003933926666093022,-0.003650237286281727

+3.774121,-0.0134901013225317,-0.05567409470677376,0.6701323390007019,-0.01362150560901276,-0.006123631509777378,-0.0009230826520491063

+3.7858328,-0.01381098572164774,-0.055025916546583176,0.6711861491203308,-0.014081075823145281,-0.0020652315148706607,-0.0031730039315156335

+3.7946212,-0.01381098572164774,-0.055025916546583176,0.6711861491203308,-0.014081075823145281,-0.0020652315148706607,-0.0031730039315156335

+3.8073054,-0.014110483229160309,-0.05444294586777687,0.6722440719604492,-0.014241899511081806,0.0013050510438755753,-0.004603014021126259

+3.8141369,-0.015001988038420677,-0.056497350335121155,0.672752857208252,-0.012143100733843391,-0.00024841958684401283,-0.002414799323560101

+3.826829,-0.015366788022220135,-0.05503644794225693,0.673516035079956,-0.012657496423924523,0.0028101585245729416,-0.003325446172534394

+3.8356088,-0.015891438350081444,-0.05750049650669098,0.6739911437034607,-0.010222579342684335,0.001852258540780493,-0.002007363299312457

+3.8473252,-0.01634332910180092,-0.05515134707093239,0.6747003793716431,-0.01063014889102414,0.004312458944659833,-0.003034319690804856

+3.8548936,-0.016680393368005753,-0.057844121009111404,0.6752240657806396,-0.008173467584502736,0.0035941906129087005,-0.001983783173743819

+3.8666137,-0.017124198377132416,-0.055093444883823395,0.6759329438209534,-0.008965725744103663,0.00638644284361705,-0.004097734072791059

+3.8744094,-0.01737065054476261,-0.05789554864168167,0.676519513130188,-0.007099297160080841,0.005772671502211882,-0.003103463401647357

+3.8880795,-0.01778285577893257,-0.054904088377952576,0.6772164106369019,-0.008407390730158342,0.009324707385963624,-0.0063601518129059445

+3.8939756,-0.018039017915725708,-0.057759109884500504,0.6777932047843933,-0.006238582799322307,0.008691955592377123,-0.0052695964314042245

+3.9066187,-0.018311701714992523,-0.05469502508640289,0.6782538294792175,-0.007340227301550104,0.011905048504319045,-0.007675733951695509

+3.9154023,-0.018531939014792442,-0.05768020078539848,0.6789300441741943,-0.0053443326438328284,0.011312073221305822,-0.00650798954319113

+3.9271185,-0.018734699115157127,-0.05448361113667488,0.6793414950370789,-0.006737021720416013,0.013598677430207637,-0.008652254830035611

+3.9329705,-0.018975527957081795,-0.057506442070007324,0.680008590221405,-0.005423949108035599,0.012984311715562469,-0.00741891976711795

+3.9476106,-0.019038125872612,-0.05433538183569908,0.6802938580513,-0.006564898422252396,0.014843089606946542,-0.009332028907188728

+3.9543467,-0.01923573948442936,-0.057373154908418655,0.6810562610626221,-0.004972564803601324,0.014284057277948722,-0.007998503977528739

+3.9680101,-0.019153205677866936,-0.05415533855557442,0.6812689900398254,-0.006029088270793428,0.016058983853555142,-0.00921307797227407

+3.9748426,-0.019381936639547348,-0.057300418615341187,0.6820451617240906,-0.004209886832507726,0.01546243128135512,-0.007740168486836122

+3.9855832,-0.01909264549612999,-0.05399812012910843,0.6817172765731812,-0.005558640552669669,0.016552918512311936,-0.00900919326897857

+3.9953384,-0.01948457956314087,-0.05707816407084465,0.683019757270813,-0.003953023512822581,0.01585975324511166,-0.00714905136383937

+4.0060779,-0.019205747172236443,-0.053872670978307724,0.6833215355873108,-0.005409876321870031,0.017083288190798077,-0.008454304584535182

+4.013883,-0.019485194236040115,-0.05696028098464012,0.6840336918830872,-0.0037779280793783804,0.016455051374650198,-0.006855504029500271

+4.026577,-0.019043587148189545,-0.05372121185064316,0.6837639808654785,-0.005053914800799631,0.017457323295176068,-0.008771401001824202

+4.0353546,-0.01936820149421692,-0.05673326551914215,0.6850752234458923,-0.003615100346568701,0.01667113193263406,-0.0070858322068081256

+4.0461032,-0.018855687230825424,-0.053596433252096176,0.684718132019043,-0.004672943812409618,0.017242718654261205,-0.008788838711096265

+4.0548751,-0.019144175574183464,-0.05660894513130188,0.6860214471817017,-0.003157657533699483,0.01618620172721033,-0.006966418430517111

+4.0656103,-0.018573323264718056,-0.05340678617358208,0.6856440901756287,-0.004384001699525608,0.016358095865779028,-0.008666879892607808

+4.0743949,-0.018836908042430878,-0.05642322450876236,0.6869183778762817,-0.003533287861489504,0.01503520225915505,-0.006500293588954801

+4.0870828,-0.018223833292722702,-0.053193598985672,0.6865664720535278,-0.0047489534902483855,0.015071049523526689,-0.007922592441166937

+4.0939146,-0.018468160182237625,-0.056155648082494736,0.6877672076225281,-0.003388889973496204,0.01381012379148382,-0.005664542244177116

+4.1066031,-0.017816640436649323,-0.05299895629286766,0.6873903870582581,-0.004570400561704154,0.01402994538688351,-0.0071471636155546895

+4.1144107,-0.018054034560918808,-0.05597672238945961,0.6885140538215637,-0.003206785663989639,0.012676260490331851,-0.004953427608193751

+4.1261229,-0.017408721148967743,-0.05277937278151512,0.6881883144378662,-0.004513110498877644,0.01262604084968926,-0.006461269574159719

+4.1349066,-0.017582891508936882,-0.05572744831442833,0.6893096566200256,-0.0033660551496555824,0.011034546798598364,-0.004230076740299451

+4.1456434,-0.01692774146795273,-0.05254125967621803,0.6889966726303101,-0.004576563427124322,0.010865793477799007,-0.005826092632545259

+4.1535007,-0.017122581601142883,-0.05546851456165314,0.6899746656417847,-0.003287103213643038,0.009458868486243057,-0.003702644489630016

+4.1661426,-0.01647067628800869,-0.052250683307647705,0.6896746158599854,-0.004411576400473787,0.009675529898379916,-0.005170220379798437

+4.1739521,-0.016611119732260704,-0.055159348994493484,0.6906845569610596,-0.003125155248468703,0.008600739579539387,-0.0029381856996305586

+4.1856624,-0.015920912846922874,-0.0519244521856308,0.690342903137207,-0.004380812772670685,0.008768209151014915,-0.00441806244962814

+4.1944418,-0.016066640615463257,-0.054906535893678665,0.6913272738456726,-0.003194414375905793,0.007514775258144167,-0.00203950367595115

+4.2071306,-0.015347335487604141,-0.05163984373211861,0.6909899711608887,-0.0044700847802965574,0.00775769919890778,-0.0034900236231599708

+4.2129911,-0.01552533358335495,-0.05459586903452873,0.6918981075286865,-0.0034870963825199565,0.006283258606741267,-0.0012062000584732438

+4.2266549,-0.014798476360738277,-0.051241278648376465,0.6916080713272095,-0.004697430058907124,0.006133459790269793,-0.002980987012678709

+4.234463,-0.014974799938499928,-0.05424648895859718,0.6925273537635803,-0.003942046429545039,0.004476193722832031,-0.000924725483006873

+4.2461744,-0.014223548583686352,-0.05094058811664581,0.692203164100647,-0.004975444922178735,0.004183672528074343,-0.0025161343896542418

+4.2549546,-0.01390495989471674,-0.05073040351271629,0.6927585601806641,-0.005044407512621599,0.0030984054593389573,-0.0021098739321924204

+4.2656944,-0.013186955824494362,-0.049251507967710495,0.6925851106643677,-0.006116995718697297,0.002447609567386294,-0.0028808272305645114

+4.2744794,-0.013665590435266495,-0.05258018895983696,0.6933912038803101,-0.004948312323990538,0.00014914124147164532,0.0007249022865248518

+4.2861865,-0.01289544627070427,-0.05000457540154457,0.6931434869766235,-0.006091981714717065,-0.00013048734187596546,-0.00021546686610218367

+4.2939944,-0.013205943629145622,-0.052910394966602325,0.6939134001731873,-0.005120327516264914,-0.0021331197793035303,0.0030171343862565713

+4.3066869,-0.012451295740902424,-0.049936242401599884,0.6936216354370117,-0.006028313550258506,-0.002240144064523977,0.0021805208654960217

+4.3135299,-0.012135390192270279,-0.04974101111292839,0.6941027641296387,-0.005928016653489655,-0.0029772910969501376,0.0031612872124341163

+4.3262026,-0.01142474077641964,-0.048428039997816086,0.6939074397087097,-0.006978238975698803,-0.002944597299978416,0.0029568154454461372

+4.334015,-0.01204649917781353,-0.051481712609529495,0.6945685744285583,-0.005694432397206207,-0.004951417873177661,0.006738049921449592

+4.3457269,-0.011330058798193932,-0.0491175539791584,0.69431471824646,-0.0067573261914053925,-0.004574678882661064,0.0053596165419534355

+4.3545075,-0.01175055094063282,-0.05193033441901207,0.6948781609535217,-0.005590898126765094,-0.005931942525786826,0.008034271191298186

+4.3662188,-0.011123770847916603,-0.04908398166298866,0.6946101784706116,-0.006922298596284091,-0.00577519402391018,0.00638033073903328

+4.3740277,-0.010863601230084896,-0.04895297437906265,0.6949419975280762,-0.007021694290191325,-0.006457983930238555,0.0065889932382580145

+4.3857423,-0.010266449302434921,-0.04761776328086853,0.6948208808898926,-0.008056509001982135,-0.006821989788092175,0.005502522366821226

+4.3945228,-0.010907755233347416,-0.05068624019622803,0.6954329609870911,-0.0069989705593166114,-0.009090634731138494,0.008292146998815536

+4.4062343,-0.010302603244781494,-0.04828987270593643,0.6952216625213623,-0.008077739971300702,-0.00912637027238929,0.006561087214397819

+4.4140428,-0.010081269778311253,-0.0481807179749012,0.6956033110618591,-0.008058566114173604,-0.009679953308365874,0.006890817398360835

+4.4267312,-0.009540651924908161,-0.047038063406944275,0.6955925822257996,-0.009074207058197132,-0.009363703905419242,0.0060766596216929895

+4.4345429,-0.0103387963026762,-0.04997345805168152,0.696236252784729,-0.007652746410491347,-0.010830292216469405,0.009218079697624592

+4.4462502,-0.009768571704626083,-0.04781663417816162,0.696051836013794,-0.00869547983654371,-0.009997088993035709,0.007583110680510213

+4.4540624,-0.00960368663072586,-0.047752249985933304,0.6964447498321533,-0.008636626632781357,-0.009732627851859767,0.00786450766930932

+4.4657698,-0.009104575961828232,-0.04669135808944702,0.6963960528373718,-0.00970470034386464,-0.008974787768420544,0.006932366127296206

+4.4735783,-0.00995232630521059,-0.0495120994746685,0.6970211267471313,-0.008411826245530324,-0.010266889890926811,0.010019162676940523

+4.4862664,-0.009464286267757416,-0.04750300198793411,0.69684898853302,-0.009360947064706467,-0.009478545219080238,0.008165156381138579

+4.4940745,-0.009355030953884125,-0.047486964613199234,0.6971999406814575,-0.009327462247208837,-0.009596634825097022,0.008160600073849736

+4.5067619,-0.008936614729464054,-0.04642268642783165,0.6972091197967529,-0.010289636505543905,-0.009086263172137647,0.007081319247526987

+4.5145705,-0.00978114828467369,-0.04924957826733589,0.6979226469993591,-0.008689273698386634,-0.0105317227960125,0.009989671808589168

+4.5262828,-0.009318252094089985,-0.04726267606019974,0.69771808385849,-0.009435315265090536,-0.00979636384979181,0.008430284845153955

+4.5340904,-0.009926029480993748,-0.04999978467822075,0.6983752250671387,-0.00788581878758183,-0.01085408111404887,0.01055165109826159

+4.545803,-0.009557846933603287,-0.047330837696790695,0.6981983184814453,-0.008733079201190841,-0.010043338356975242,0.008849691786298006

+4.5545865,-0.0101058604195714,-0.05014314129948616,0.6988544464111328,-0.007004590066136044,-0.010648066679596436,0.01039272025624235

+4.5662989,-0.009800855070352554,-0.04725795239210129,0.6986861228942871,-0.00801662490985681,-0.009592297002297795,0.008292174732062748

+4.5741067,-0.01027985941618681,-0.0501721128821373,0.6994067430496216,-0.006235518004737164,-0.00984407437997938,0.009214520347934822

+4.5858185,-0.009966237470507622,-0.047053154557943344,0.6991451978683472,-0.007235389498949499,-0.008402758790432344,0.0068344003077401615

+4.594603,-0.010413945652544498,-0.05010928213596344,0.6999338865280151,-0.005884718491248962,-0.008194704467390583,0.0075782775628497065

+4.6063156,-0.010092719458043575,-0.04691673070192337,0.699592113494873,-0.00693956718420256,-0.006365856977226882,0.005109676319781041

+4.6131468,-0.010525346733629704,-0.050053805112838745,0.7004090547561646,-0.005335952828038042,-0.006008098486294977,0.0059150751240442355

+4.6258807,-0.010241293348371983,-0.04684663936495781,0.7001315355300903,-0.006301490520331431,-0.004476029944688275,0.00345692768571056

+4.6336682,-0.010685425251722336,-0.050081029534339905,0.7009992003440857,-0.004911002987751996,-0.004666524921699956,0.004455804264958133

+4.6463352,-0.01041003130376339,-0.04687121883034706,0.7007663249969482,-0.005995564720860024,-0.003572507685573751,0.002497761146904273

+4.6551346,-0.010474149137735367,-0.04693719372153282,0.7012161612510681,-0.0059842929816106075,-0.003226113691597502,0.0025575971314479662

+4.6668293,-0.01016655657440424,-0.04544862359762192,0.7011611461639404,-0.007001510258403134,-0.0024487844951336622,0.0013729701835252723

+4.674332,-0.010197415016591549,-0.04542716592550278,0.7016311287879944,-0.007044732278350211,-0.0025011768543302905,0.001510689062391034

+4.6854606,-0.011357692070305347,-0.04880288988351822,0.7025089859962463,-0.0053325072861749815,-0.004118437807540912,0.005393738720907714

+4.6942764,-0.01150624267756939,-0.049058206379413605,0.7030890583992004,-0.0052900736891524636,-0.003843944898876938,0.0055492255605356176

+4.7069335,-0.012441795319318771,-0.05070183426141739,0.7035946846008301,-0.0033386324614070283,-0.004652634938929949,0.007676599974178469

+4.7137638,-0.012666243128478527,-0.05111198127269745,0.7041664123535156,-0.0033749527420547853,-0.004554239413428292,0.007695579956283207

+4.7254834,-0.01323559321463108,-0.05186264589428902,0.7044790387153625,-0.0014733739357153286,-0.004368455065610387,0.008158757416588861

+4.7332883,-0.01349567249417305,-0.052336711436510086,0.7050032615661621,-0.0017288991760767876,-0.0037431889065522514,0.007348903727050737

+4.7459726,-0.013773485086858273,-0.052712999284267426,0.705190896987915,-0.00043750520011448367,-0.002788378715875169,0.005736712287912979

+4.7537804,-0.014040357433259487,-0.05318894609808922,0.705653727054596,-0.0007637264411589881,-0.0015128477687509564,0.003720016261601033

+4.7664701,-0.014061792753636837,-0.05325547233223915,0.7057425379753113,0.0007751546816190617,0.0002522357554392796,0.0004105383150606769

+4.7743003,-0.01431048009544611,-0.05368093028664589,0.7061610221862793,0.0005048514901315133,0.0018118489858190135,-0.0021795932843423622

+4.7859882,-0.014212539419531822,-0.05359558016061783,0.7062353491783142,0.0019113011385537356,0.0034879338918960496,-0.005572955761166543

+4.7937965,-0.014429780654609203,-0.05394808575510979,0.7066076993942261,0.001571988461079539,0.004588171778524211,-0.007592846682954674

+4.8042845,-0.014643183909356594,-0.054294317960739136,0.7069578766822815,0.0012389939220590423,0.005419722539765528,-0.00893063934826426

+4.8151359,-0.01485180202871561,-0.054632630199193954,0.7072885036468506,0.0008351877962858303,0.005716556973720575,-0.009715921612624105

+4.8248964,-0.015055030584335327,-0.054961908608675,0.7076079249382019,0.0004310518993489396,0.005985869572343589,-0.010293987780418864

+4.8334363,-0.015252547338604927,-0.055281415581703186,0.7079231142997742,9.160174134606518e-05,0.006376418533517501,-0.010474419467744005

+4.8441723,-0.015444040298461914,-0.05559080094099045,0.708232045173645,-0.00023807915084321512,0.006757696725056716,-0.010490345948989727

+4.8539324,-0.015629148110747337,-0.05588999763131142,0.7085320353507996,-0.0005285610473795517,0.007025297164149129,-0.01056575660518086

+4.8646638,-0.0158074963837862,-0.05617888271808624,0.7088310718536377,-0.0007406926638931872,0.007154179910227487,-0.010637958581843526

+4.8744239,-0.015978755429387093,-0.05645718798041344,0.7091475129127502,-0.001013997229406833,0.007216965989481302,-0.01113526622718958

+4.8841884,-0.016142752021551132,-0.05672450363636017,0.7094917893409729,-0.0012800784453243848,0.007371891802783758,-0.011883807154452117

+4.8929678,-0.016299398615956306,-0.05698024481534958,0.7098598480224609,-0.0014564241446221003,0.007649319586962242,-0.012994191439936855

+4.9037084,-0.01644856669008732,-0.05722363293170929,0.7102394104003906,-0.0016702680541957596,0.008029541723301148,-0.014451600718721334

+4.9144444,-0.016590062528848648,-0.05745364725589752,0.7106136679649353,-0.0018681181135314594,0.008378204048150406,-0.015832147861873636

+4.9242001,-0.016723595559597015,-0.05766903981566429,0.7109746336936951,-0.0020096636287322924,0.008861593932337082,-0.016885333292382027

+4.9339643,-0.01684872806072235,-0.05786856636404991,0.7113260626792908,-0.0021804593932771375,0.009164123028356948,-0.017929104334957296

+4.9437244,-0.016965091228485107,-0.058051250874996185,0.7116655111312866,-0.002341258552361902,0.009517451585133771,-0.018879556076493255

+4.9535492,-0.017072346061468124,-0.05821609869599342,0.7119948863983154,-0.0025903464467807364,0.009687556704278118,-0.019822036230835026

+4.9642157,-0.017170198261737823,-0.05836212635040283,0.7123172283172607,-0.0028533563192729215,0.009797336579693837,-0.02057344315983336

+4.9739775,-0.017258567735552788,-0.058488648384809494,0.712626039981842,-0.0030661007317268766,0.00973404476813813,-0.02127069236150495

+4.9837361,-0.017337355762720108,-0.05859481543302536,0.7129282355308533,-0.0032631037540854415,0.009573997756141468,-0.021886559031113435

+4.9935004,-0.017406634986400604,-0.058679915964603424,0.7132270336151123,-0.00337371189096725,0.009385573734382965,-0.02238122531784624

+5.0042325,-0.017466649413108826,-0.058743592351675034,0.7135142683982849,-0.0035375715731841033,0.009435051856118717,-0.023017482619497185

+5.0139916,-0.017517415806651115,-0.05878518894314766,0.7137946486473083,-0.0036602347924929034,0.009218350682800221,-0.023654511120113613

+5.0247284,-0.017559047788381577,-0.05880417674779892,0.714064359664917,-0.0038133834932253608,0.008971621760089936,-0.024282332979201553

+5.0335165,-0.01759188435971737,-0.05880027636885643,0.7143096923828125,-0.003989032233857327,0.008520132587156509,-0.02523515402149831

+5.0432726,-0.017616206780076027,-0.058772627264261246,0.7145352959632874,-0.004117061408293519,0.008364610696998813,-0.026480108399062754

+5.0530318,-0.017632195726037025,-0.05871982499957085,0.7147541642189026,-0.004258124342969325,0.0083017852910405,-0.02785312885818129

+5.0637723,-0.017639921978116035,-0.0586404874920845,0.7149698138237,-0.004394131499487628,0.008110199596760457,-0.029164429092754397

+5.0745057,-0.017639420926570892,-0.05853303521871567,0.715191662311554,-0.004567827615679224,0.007825275221124982,-0.03034072609192815

+5.0832879,-0.01763072982430458,-0.058395497500896454,0.7154436707496643,-0.004767802602631116,0.007835315565053489,-0.031172299846891387

+5.0930523,-0.017613928765058517,-0.05822669342160225,0.7157310247421265,-0.004972972624573934,0.007818790059255492,-0.03189718717071441

+5.1037886,-0.017589161172509193,-0.05802644416689873,0.7160348892211914,-0.005164246581576156,0.0076066715666367754,-0.0326211623519554

+5.1125722,-0.01755663938820362,-0.057794488966464996,0.7163414359092712,-0.0053135309796468345,0.007450492716500095,-0.033239799840911195

+5.1242804,-0.0175166018307209,-0.057530444115400314,0.7166422605514526,-0.005386259279529391,0.007280514216882316,-0.03387803100104173

+5.1340438,-0.017469286918640137,-0.05723408982157707,0.7169259190559387,-0.005444956955650343,0.007362146172217904,-0.03443262398336241

+5.1437999,-0.01741470769047737,-0.05690471827983856,0.7171962857246399,-0.00552918121073227,0.007168472903265423,-0.035035669709057124

+5.1545358,-0.017352944239974022,-0.05654193460941315,0.7174485325813293,-0.0056484266772849935,0.007046008825644767,-0.03570457873621536

+5.1633243,-0.01728416606783867,-0.05614525452256203,0.7176792025566101,-0.005770271469830044,0.006700033143963878,-0.036638600245342344

+5.1740565,-0.0003165473463013768,-0.03386150673031807,0.7093785405158997,-0.008588117128508476,0.012934856484927973,-0.046916183863471544

+5.1838159,0.00033405842259526253,-0.032610923051834106,0.7093365788459778,-0.00859845477419298,0.012245658515173159,-0.0478147644830483

+5.1936359,0.0009328952874056995,-0.03150232508778572,0.7088243961334229,-0.010151726137234585,0.011484238755688603,-0.048751681174379606

+5.2033369,0.0016061661299318075,-0.030169779434800148,0.7087389826774597,-0.009947780596912707,0.010523932094804447,-0.04933674757531566

+5.213096,0.0015946681378409266,-0.02891208603978157,0.7082884907722473,-0.010604081114407306,0.008489765895835963,-0.048011333047485796

+5.2238806,0.002259109867736697,-0.027509327977895737,0.7082015872001648,-0.010304598517232255,0.005876446649379161,-0.04536016062643488

+5.2326158,0.0017738930182531476,-0.025927267968654633,0.7076466083526611,-0.011174655725377984,0.0011767003716963485,-0.04005640856918102

+5.2433564,0.0023923006374388933,-0.024476857855916023,0.7076082825660706,-0.010915839282368268,-0.0029812294881877838,-0.03497589329213846

+5.2531164,0.0015831687487661839,-0.022972943261265755,0.7069253325462341,-0.01194800620490135,-0.008191806963936055,-0.028642892921712435

+5.2638478,0.002126137027516961,-0.021514486521482468,0.7069323658943176,-0.011833444177424093,-0.011996712100120611,-0.023871295175303852

+5.2736131,0.0013112728483974934,-0.020093895494937897,0.7063649296760559,-0.013385141838692678,-0.016196036883320067,-0.019053650423298044

+5.2833692,0.0017606986220926046,-0.018657106906175613,0.7063522934913635,-0.013218623121240794,-0.01844366901559529,-0.016711661582487016

+5.2950848,0.001158911269158125,-0.01740841567516327,0.7057985067367554,-0.01485853098504657,-0.020836351873137555,-0.014443433459366066

+5.3028963,0.001515397452749312,-0.016006087884306908,0.7057434320449829,-0.014524567205168017,-0.02165249001484623,-0.014547478457995533

+5.3136279,0.0011981962015852332,-0.014872059226036072,0.7053622603416443,-0.015539144480494217,-0.022377484640365517,-0.014588502967170047

+5.3233837,0.001471213879995048,-0.01349494606256485,0.705316960811615,-0.015068833919661694,-0.022169397112285258,-0.01593084790901304

+5.3341245,0.001387452706694603,-0.012422118335962296,0.7051119208335876,-0.016025329362734746,-0.02189638412372378,-0.01656704517250582

+5.3438846,0.0015896937111392617,-0.011054391972720623,0.7051374912261963,-0.01567437630710176,-0.021275823999499066,-0.017700419414702153

+5.3536445,0.0016631046310067177,-0.010080892592668533,0.7051534652709961,-0.016715679331712627,-0.021258671855085256,-0.01793417012253741

+5.3644367,0.004703653044998646,-0.014072230085730553,0.7074260711669922,-0.014332855099119511,-0.022562864609212776,-0.01381012080655378

+5.3731613,0.005250298883765936,-0.01258965115994215,0.7073990106582642,-0.01564482070581569,-0.021816843260073115,-0.014946823353277282

+5.3839158,0.005319364834576845,-0.011458619497716427,0.7076120972633362,-0.015286578241983328,-0.021826353697374304,-0.014986634782335839

+5.3927079,0.005794778000563383,-0.00987280160188675,0.7077073454856873,-0.01664309952094871,-0.021263104762893406,-0.01620849831686828

+5.4034163,0.0058622341603040695,-0.008657337166368961,0.7079688310623169,-0.01629477049604517,-0.02130528035876026,-0.017425383877273735

+5.4121998,0.00628515612334013,-0.007123933173716068,0.7081246972084045,-0.017188532608277882,-0.020841981210681447,-0.020095819032870887

+5.4239165,0.006344284862279892,-0.005832803435623646,0.7084460854530334,-0.01681849155842892,-0.02057744055963833,-0.022932347653681875

+5.4336718,0.006383052095770836,-0.004519726615399122,0.7087873220443726,-0.016336109951169575,-0.020248966157765492,-0.02644220428011061

+5.4434317,0.006401645950973034,-0.0031813238747417927,0.7091559767723083,-0.015807090401209492,-0.019863006749835023,-0.02979503729645372

+5.4541881,0.00640042033046484,-0.0018140457104891539,0.7095546722412109,-0.015304937430404852,-0.019459408208511334,-0.03290719208916699

+5.4902819,0.004118811804801226,-0.0030910747591406107,0.7097829580307007,-0.011883873999152127,-0.021697903005877442,-0.033121879854004645

+5.497495,0.0038708162028342485,-0.0019314284436404705,0.7102559208869934,-0.011883873999152127,-0.021697903005877442,-0.033121879854004645

+5.5011277,0.0025423159822821617,-0.0017213192768394947,0.7105738520622253,-0.00910690102241351,-0.02278662599514127,-0.032848343805852664

+5.5069897,0.0021631205454468727,-0.0005973335355520248,0.7111025452613831,-0.008777825968345606,-0.021895750542652186,-0.03610330017623255

+5.5099105,0.001761763240210712,0.0005601434968411922,0.7116414308547974,-0.008777825968345606,-0.021895750542652186,-0.03610330017623255

+5.5138673,0.0013386846985667944,0.0017527724849060178,0.7121915221214294,-0.008692431796069123,-0.020587452192689523,-0.03877877531009966

+5.5236605,0.0007578472141176462,0.0031756109092384577,0.7122262716293335,-0.006406835127685806,-0.0188316295968332,-0.042221531764899706

+5.5333343,0.00028611556626856327,0.0044608283787965775,0.7127630710601807,-0.006317319105314194,-0.01649240086635334,-0.04607681748911029

+5.5430994,3.9084079617168754e-05,0.006253156345337629,0.7129294872283936,-0.0038368164281486804,-0.013514857648856215,-0.050832141569475596

+5.5538303,-0.0004927004920318723,0.00781491119414568,0.713455855846405,-0.0038484300971181697,-0.010888428553259019,-0.05549483128644285

+5.5642287,-0.0009884040337055922,0.00928838923573494,0.7139163613319397,-0.004007560974470329,-0.008630607161285778,-0.05941575845106858

+5.5739883,-0.001493381685577333,0.010817847214639187,0.714368462562561,-0.00411788366249733,-0.006625991575115395,-0.06266737941857785

+5.5837442,-0.0012392356293275952,0.013519411906599998,0.7142753601074219,-0.0022800668335524036,-0.003711816461474142,-0.06687240418089095

+5.5935042,-0.0016938187181949615,0.015277053229510784,0.7146749496459961,-0.002266631783821306,-0.0019608450933643637,-0.06871330465831407

+5.6042448,-0.0016058930195868015,0.017903059720993042,0.7146772742271423,-0.00012639791864551525,0.00018032610083692808,-0.071180228769471

+5.6130243,-0.0020191101357340813,0.019872181117534637,0.7150401473045349,-0.0003645221204836826,0.000941198952239686,-0.07260271523152952

+5.623761,-0.0024317449424415827,0.0219116173684597,0.7153982520103455,-0.0005316098392876677,0.0018195308949057031,-0.0735760371376265

+5.6335248,-0.002843021648004651,0.024021510034799576,0.7157377600669861,-0.0007847482931972957,0.0025463163804356546,-0.07446745017263272

+5.6432816,-0.0026500634849071503,0.02725701406598091,0.715621829032898,0.0007550066394065804,0.00393229359106908,-0.07671299622865826

+5.6530412,-0.003002898534759879,0.029606854543089867,0.7158868908882141,0.0006062805335717509,0.004256035455661912,-0.07714661238017596

+5.6635215,-0.0030444220174103975,0.03268131613731384,0.7158872485160828,0.0016356809456805359,0.005236003388320481,-0.07868889105672348

+5.6742579,-0.0033593561965972185,0.0352378711104393,0.7160935997962952,0.0013538783277335543,0.0055538866314617345,-0.07924452618861257

+5.6840173,-0.0034867359790951014,0.038355905562639236,0.7161570191383362,0.002431140737824455,0.006284412706187351,-0.08035121233249402

+5.6937817,-0.003770510433241725,0.041109368205070496,0.7163355350494385,0.00207768335817532,0.006264104123491674,-0.08062071164137334

+5.7035373,-0.003941097762435675,0.04430082440376282,0.7164084911346436,0.003007948366348716,0.006630350412026465,-0.08116126786794028

+5.7132973,-0.0041988082230091095,0.04724150151014328,0.7165428996086121,0.0026097150645767128,0.006679017827166551,-0.08082632609869908

+5.7230574,-0.00441385991871357,0.05052021145820618,0.7165893316268921,0.002966237037995902,0.007096484496980059,-0.08031094667688887

+5.7337932,-0.004650649148970842,0.053638577461242676,0.716675341129303,0.0024554762253465217,0.0070003907940068425,-0.07894451722306456

+5.7435573,-0.004875091835856438,0.05699431151151657,0.7166569232940674,0.002830393723653175,0.007024275445744569,-0.07761611441906058

+5.7533134,-0.005094853695482016,0.06027821823954582,0.7166904807090759,0.002280670902125041,0.00696212231869072,-0.0763651540739164

+5.7630734,-0.005334018263965845,0.06371557712554932,0.7167020440101624,0.0024540944157396645,0.0070795093509980105,-0.07496578109274014

+5.7738097,-0.005540044978260994,0.0671529546380043,0.7167032957077026,0.0019517608921039342,0.006962580923987793,-0.07362870557606092

+5.7835693,-0.005771176889538765,0.07064446806907654,0.7166335582733154,0.0020809237587625378,0.0067083653691837105,-0.07243093796096832

+5.79333,-0.005967212375253439,0.07422332465648651,0.7166111469268799,0.0015655706382405334,0.006433559290640046,-0.07141437815767684

+5.8030896,-0.006131055299192667,0.07775134593248367,0.7166255712509155,0.0017851139422586297,0.0060435660275745045,-0.07033171508320253

+5.8138498,-0.006317391991615295,0.08145976811647415,0.7165851593017578,0.0011968822837411842,0.0056433017966710025,-0.06915736734513958

+5.8245625,-0.006425499450415373,0.08502242714166641,0.7165898680686951,0.0013061829296431345,0.005229469429630975,-0.06753679888896444

+5.8323699,-0.006604008376598358,0.08885177969932556,0.7165606021881104,0.0006710116878638512,0.004787521724557976,-0.06619047714733992

+5.8431058,-0.006703144870698452,0.09250125288963318,0.7165340781211853,0.0005823069724046044,0.0043443136335460306,-0.06470850010991071

+5.8528929,0.010576503351330757,0.08906671404838562,0.7112454771995544,-0.0031641406501079225,0.010868260639537948,-0.06460402736389523

+5.8626509,0.010700630955398083,0.09346747398376465,0.7106755375862122,-0.0034412866159394292,0.010424087177815722,-0.06305037643314108

+5.8730825,0.011151188053190708,0.09751694649457932,0.7105917930603027,-0.0039492743433838335,0.010145818968701537,-0.061927370518416874

+5.8838231,0.01143107283860445,0.10155263543128967,0.7102738618850708,-0.004574503473217861,0.00886444572059901,-0.06007031835678607

+5.89263,0.013581912033259869,0.1068560779094696,0.7107388973236084,-0.006679505087775816,0.00876628952348833,-0.06137807481239576

+5.9023673,0.013725644908845425,0.10999578982591629,0.710112452507019,-0.006394434139337564,0.004929879519451984,-0.058875277967803945

+5.9141646,0.014931047335267067,0.11573907732963562,0.7108688950538635,-0.007920252818383705,0.001849722519446773,-0.05929317212661312

+5.9239268,0.015149359591305256,0.11762624979019165,0.7100911736488342,-0.0071925248519660034,-0.0033720999249009344,-0.05630013774683093

+5.9326775,0.015997979789972305,0.12381318211555481,0.7110003232955933,-0.008989071983766934,-0.007421639846816654,-0.05564679744038841

+5.9424327,0.016260607168078423,0.12515251338481903,0.7101330161094666,-0.009000363090503947,-0.012475562783600187,-0.05304890791803945

+5.952242,0.016955289989709854,0.13153183460235596,0.7111459970474243,-0.011074909540724655,-0.016324098155205007,-0.051949929036695146

+5.962663,0.017109153792262077,0.13279373943805695,0.7100158333778381,-0.010862942149155615,-0.020614401307291343,-0.04901517636502729

+5.9733991,0.017650531604886055,0.13930365443229675,0.7111549973487854,-0.012052049587931116,-0.02325905322125177,-0.04774769157167502

+5.983159,0.017717180773615837,0.14063002169132233,0.709918737411499,-0.011710099701224804,-0.02584272797612227,-0.04464632862418048

+5.9929191,0.018138721585273743,0.14724427461624146,0.7111843228340149,-0.013468209082316962,-0.026911983081286697,-0.04343793273998124

+6.002675,0.018072089180350304,0.14874807000160217,0.7098400592803955,-0.013210016635253199,-0.028484597696541786,-0.0409468989022995

+6.0134151,0.018364066258072853,0.15541088581085205,0.7112178206443787,-0.014642834605637051,-0.02881653510432014,-0.040144697876573314

+6.023171,0.018155181780457497,0.15712562203407288,0.7097643613815308,-0.014204189536436181,-0.029969823168124774,-0.03764149333777322

+6.032935,0.01833152398467064,0.16379278898239136,0.7111696600914001,-0.01567969189584477,-0.030303306977933753,-0.036996705140063826

+6.0426904,0.01800999604165554,0.1656375676393509,0.7096679210662842,-0.014704116270344427,-0.03161385839383453,-0.03486649443822418

+6.0534279,0.018042201176285744,0.17229902744293213,0.7111379504203796,-0.016108909424663642,-0.03208896548648453,-0.034459063318047475

+6.0638601,0.01763000339269638,0.174307718873024,0.7096595168113708,-0.015399856550080235,-0.03349231092399342,-0.03190775928169751

+6.07362,0.017560282722115517,0.18100297451019287,0.71115642786026,-0.01695031504004008,-0.0344417645463232,-0.031220101063531482

+6.0833828,0.0170658640563488,0.1830918937921524,0.7097166776657104,-0.01616208485423985,-0.03578099260155291,-0.02868419217752548

+6.0932078,0.016907911747694016,0.18969275057315826,0.7111329436302185,-0.017320471695601573,-0.03598091855913594,-0.027914286432794592

+6.1029027,0.016293946653604507,0.19196797907352448,0.7096766829490662,-0.016264142482928904,-0.0365183815513639,-0.025531153988778733

+6.113634,0.016013693064451218,0.1985323131084442,0.7111149430274963,-0.017570109419815932,-0.03587270060662859,-0.025025571115647235

+6.1243714,0.015303292311728,0.20092757046222687,0.7096968293190002,-0.01652735140498666,-0.0355763578085478,-0.022750598849624416

+6.133159,0.014918255619704723,0.20747597515583038,0.7111470699310303,-0.017801789192416484,-0.03458438794242807,-0.022315048776838473

+6.1429189,0.014098376035690308,0.21001103520393372,0.7097254991531372,-0.01666990655896312,-0.033752309554313485,-0.02007034297368556

+6.1526744,0.013651985675096512,0.2164861261844635,0.7110652327537537,-0.018008768628969808,-0.03199607054455894,-0.019559268211393015

+6.163388,0.012779227457940578,0.21909469366073608,0.7097082138061523,-0.016506115656772218,-0.030665559106128986,-0.017303790356865214

+6.1731351,0.012283544056117535,0.22553762793540955,0.7109222412109375,-0.017570872582576284,-0.02867487195651216,-0.016701114870535955

+6.1829198,0.011341105215251446,0.2282496839761734,0.7095353007316589,-0.01607486906947852,-0.02725126838788735,-0.014690920749750858

+6.192946,0.010739904828369617,0.2346908003091812,0.7107495069503784,-0.0174638708027387,-0.02513879966763168,-0.014287302149611422

+6.2027058,0.009788217954337597,0.2375558614730835,0.7095056176185608,-0.01606721585510891,-0.02344339559462325,-0.012314904089905501

+6.2134421,0.009112893603742123,0.24387772381305695,0.7106456160545349,-0.0176578227259361,-0.021118809833067805,-0.011928674994500996

+6.2241794,0.00811892468482256,0.24682268500328064,0.7095180749893188,-0.016319798313348895,-0.0191888035059517,-0.01011467084651286

+6.2339398,0.007431137841194868,0.2531047761440277,0.7106108069419861,-0.01762830523051496,-0.01672799336324655,-0.010022694063188533

+6.2427233,0.0064168088138103485,0.25607284903526306,0.70961993932724,-0.0160434005425295,-0.014917590720133246,-0.00854178794275042

+6.2534578,0.005750230513513088,0.2622089087963104,0.7105662226676941,-0.017238529612912324,-0.012312591765483953,-0.008552126636608742

+6.2632506,0.004705960396677256,0.26526516675949097,0.7096301913261414,-0.016022603851125635,-0.010233374856351573,-0.006785155464243643

+6.2729821,0.00402676360681653,0.2713613510131836,0.7105305790901184,-0.016993980624907947,-0.008294545183930201,-0.006496270960782343

+6.2837142,0.0029611599165946245,0.2745274305343628,0.7096364498138428,-0.01572738360539297,-0.006435769481437398,-0.004366539873622832

+6.295426,0.00233850278891623,0.2805519998073578,0.7104238271713257,-0.016951222098862014,-0.003967975010417311,-0.003509302076790449

+6.3022578,0.0012647730764001608,0.28387171030044556,0.7095977663993835,-0.015699115114717395,-0.0021201628887580256,-0.0012014622952265489

+6.312994,0.0005998313426971436,0.28972235321998596,0.7103389501571655,-0.01702145256407474,-0.0001322936356668543,-0.0001399681994313633

+6.3237311,-0.00040563984657637775,0.2929910719394684,0.7097172737121582,-0.015615250754905404,0.0015178173365592734,0.002308402528670713

+6.3334897,-0.0010126312263309956,0.2987247407436371,0.7103293538093567,-0.016930876554479838,0.0036489889482101837,0.0032977463722313584

+6.3432773,-0.002005675109103322,0.30213451385498047,0.7097523212432861,-0.015288168886523087,0.005452774171434758,0.0052589318973367966

+6.3530098,-0.0025751451030373573,0.30781760811805725,0.7103062868118286,-0.01613234325442134,0.007454668699126914,0.005744797834907706

+6.3624698,-0.003528712084516883,0.3111717402935028,0.7097405195236206,-0.01453909257655583,0.008985751082373988,0.007335100791861897

+6.3732062,-0.004084098152816296,0.3166752755641937,0.7101436257362366,-0.015730091296622,0.01075302464252895,0.007639849016909369

+6.3839473,-0.005003598518669605,0.32013389468193054,0.7095928192138672,-0.014461736522452187,0.012158908451831091,0.00915620486872273

+6.3937071,-0.005530970636755228,0.3255992531776428,0.7100141644477844,-0.015473571156495213,0.013848267175051452,0.009528247297896763

+6.4024863,-0.006380820646882057,0.3291148543357849,0.7095837593078613,-0.013969436827034666,0.014971418133972824,0.011399954378880087

+6.4122511,-0.006885843351483345,0.3344377875328064,0.7099224925041199,-0.015198171116112111,0.016157990435893534,0.012633836469676184

+6.4229837,-0.007676508277654648,0.33800044655799866,0.7095489501953125,-0.013867311215700229,0.016947368428480988,0.01502298142134735

+6.4327471,-0.008149523288011551,0.3432021141052246,0.7098146080970764,-0.015431945244847934,0.017805687936245113,0.016872314058561422

+6.4434796,-0.0088665671646595,0.34673506021499634,0.7094805836677551,-0.014269898608208875,0.018218369845698988,0.01970575017109423

+6.4532385,-0.00929687824100256,0.3518240451812744,0.7096509337425232,-0.015260643086157748,0.01893579397032007,0.02159025700460348

+6.4620545,-0.009916314855217934,0.3552740812301636,0.7094292640686035,-0.014149558230698286,0.019382352120749045,0.02395596989276208

+6.4727592,-0.010342827998101711,0.3602789342403412,0.7096753716468811,-0.015036602755428114,0.02034968333670106,0.02519593639534991

+6.482523,-0.01092398539185524,0.36367955803871155,0.7094281911849976,-0.014049300254348454,0.0209770191024053,0.027024152148611754

+6.4922788,-0.011295133270323277,0.3685857057571411,0.709656298160553,-0.015245137065588586,0.021934508615853218,0.028159841698528847

+6.5030191,-0.011820404790341854,0.37224435806274414,0.7095218300819397,-0.014321532357738267,0.02276335773735635,0.02981925170104467

+6.5117987,-0.012176002375781536,0.37696895003318787,0.7097013592720032,-0.015727493476571045,0.023445842829604272,0.03087758965704786

+6.5244871,-0.012605701573193073,0.3806796073913574,0.7097182273864746,-0.014184797574470769,0.024041562261398686,0.0321315858517932

+6.5322991,-0.01292319968342781,0.38517534732818604,0.7097875475883484,-0.015275362728354891,0.02467757916038122,0.03292515166723523

+6.5430303,-0.013287948444485664,0.38875097036361694,0.7098366022109985,-0.013923119557666619,0.024787877339243706,0.034195020401199004

+6.5537709,-0.013516994193196297,0.3931538462638855,0.7098802328109741,-0.01511129767075487,0.024774111339154144,0.035209859698961225

+6.5635263,-0.013861403800547123,0.39693740010261536,0.7099241614341736,-0.013875406212195796,0.024440216171187707,0.0370711168571805

+6.5732911,-0.014075394719839096,0.4011385142803192,0.709942102432251,-0.014792740347073011,0.024051812457096245,0.038817427674834315

+6.5830511,-0.014362093061208725,0.4048507809638977,0.7100314497947693,-0.01328539885462111,0.023211387913010428,0.04102453975467914

+6.5937824,-0.014554372988641262,0.4089256823062897,0.7100500464439392,-0.014314963689681623,0.02273824243591053,0.04284278251630844

+6.6016093,-0.01481656450778246,0.41241455078125,0.709965705871582,-0.013224456591024615,0.022046813494954662,0.044981705052527333

+6.6133033,-0.014968530274927616,0.41642749309539795,0.7100127935409546,-0.014035491960341158,0.021520045936688506,0.04683198108081752

+6.6230623,-0.0151359299197793,0.42005014419555664,0.7101635336875916,-0.012489632966755457,0.02093419363239417,0.04860533205706184

+6.6318515,-0.015279623679816723,0.4238247275352478,0.7101732492446899,-0.013244046974724229,0.02065297880710049,0.05002311723101074

+6.6435584,-0.015402271412312984,0.4273776113986969,0.710411548614502,-0.01189123955792106,0.020126422860044922,0.051215170132266875

+6.652342,-0.015504052862524986,0.4309731125831604,0.7104018330574036,-0.013032335724487356,0.01984797399818234,0.0520457055561971

+6.6621023,-0.015592338517308235,0.43471047282218933,0.7107267379760742,-0.011479503858494543,0.019335872640817865,0.05273829599128651

+6.6728402,-0.015691159293055534,0.43810781836509705,0.710655689239502,-0.012006214369519342,0.018689932545357682,0.053399789926068295

+6.682603,-0.0157289057970047,0.44172680377960205,0.7110114097595215,-0.010269921100724905,0.01789889898206391,0.05400270777795426

+6.6923634,-0.015826519578695297,0.44493693113327026,0.7109386920928955,-0.01100732049986813,0.017028171321912394,0.05487045426560667

+6.7040715,-0.015883997082710266,0.44843530654907227,0.7111830115318298,-0.009356287177861043,0.016186972999837172,0.05573663175031926

+6.7128549,-0.015922430902719498,0.4515327215194702,0.7111059427261353,-0.010329714154126762,0.015295242667414603,0.05677615698652656

+6.7235901,-0.015887731686234474,0.45511776208877563,0.7116222381591797,-0.008926699611305553,0.01442702683672946,0.057652223367236397

+6.732374,-0.015913471579551697,0.4580349028110504,0.7115039229393005,-0.010120257950658539,0.013479986780605602,0.058785653064116226

+6.7431596,-0.01585703156888485,0.4613523483276367,0.7119402885437012,-0.00917337598019416,0.012530446779920018,0.05976361336065192

+6.7528991,-0.015835871919989586,0.46453356742858887,0.7122111916542053,-0.008720702923049991,0.011715236941432183,0.06063631803474155

+6.762635,-0.015789156779646873,0.4676634967327118,0.712522566318512,-0.007530864301274867,0.011041615680068185,0.0610903831151044

+6.7714144,-0.015693509951233864,0.47022464871406555,0.7121821641921997,-0.00868166756268036,0.010562840970524066,0.06170492403238669

+6.7821551,-0.015610779635608196,0.4737701416015625,0.7128115296363831,-0.0067276797108505,0.010153370660254783,0.061588949127528374

+6.7928858,-0.015503741800785065,0.4761427342891693,0.7123801708221436,-0.007946504762908167,0.009733477852736207,0.061902560430004354

+6.8026785,-0.015319015830755234,0.4793875217437744,0.7131295204162598,-0.006004615682441566,0.00914888356510334,0.061785208389133754

+6.8133822,-0.015219607390463352,0.48187610507011414,0.7127494215965271,-0.007026033324313573,0.008465800080884402,0.06204228339057147

+6.8231426,-0.015005329623818398,0.48489367961883545,0.7134626507759094,-0.0051117446502780845,0.00789431929388743,0.06187152149571497

+6.8329073,-0.014884546399116516,0.48694175481796265,0.7130213379859924,-0.005867628459283122,0.007396862398087113,0.06206957640929651

+6.8426636,-0.014691655524075031,0.4900727868080139,0.7137237787246704,-0.003924285358978581,0.00672526699711174,0.06165651067686378

+6.852423,-0.014617279171943665,0.4919384717941284,0.7132701873779297,-0.00501841731490856,0.0056914607916845415,0.06186541636343015

+6.8631631,-0.01443861611187458,0.4950736463069916,0.7139147520065308,-0.0037315871537348133,0.0056902602382883005,0.061544827946408094

+6.8729199,-0.01430538110435009,0.49683713912963867,0.7133910059928894,-0.005210236940606008,0.004519035878034956,0.0619830554766078

+6.8826784,-0.014094993472099304,0.49979254603385925,0.7140499353408813,-0.0037811576604669227,0.0034518058018549783,0.062007678831343074

+6.892487,-0.013946528546512127,0.5020942687988281,0.7142930030822754,-0.0036034656260798925,0.0024262583122174335,0.062243228440177385

+6.9031747,-0.01376408338546753,0.5045371651649475,0.7147371768951416,-0.0020369345244982927,0.0019340961836129087,0.06221564268732423

+6.9129715,-0.013609739020466805,0.5067275762557983,0.7149773836135864,-0.0016680686359250682,0.0015891293010594314,0.06213696529823609

+6.9236711,-0.013456011191010475,0.5089752674102783,0.7152481079101562,-0.0001457291058765127,0.0011675997472740108,0.062063060167912215

+6.9324537,-0.013299542479217052,0.5110519528388977,0.7154567837715149,2.1360942881714016e-05,0.0007762050967471932,0.06222210331622269

+6.9422139,-0.013180729001760483,0.5131492018699646,0.715402364730835,0.0012223433097879582,-1.655431317967684e-05,0.06222550494973732

+6.9539283,-0.01302742213010788,0.5151122212409973,0.7155436873435974,0.001218753230449333,-0.000833596827884657,0.0621454938003268

+6.9627099,-0.012875200249254704,0.5170148611068726,0.7156767845153809,0.001295386906807929,-0.0015747824025832795,0.06186997059068927

+6.9714943,-0.012724896892905235,0.5188575387001038,0.715800404548645,0.001366762953267205,-0.0025643305690138587,0.06137771994994423

+6.983262,-0.012596307322382927,0.5208516716957092,0.7156710624694824,0.0026018002036448267,-0.003566136145974579,0.060568596969156535

+6.9939489,-0.01245409157127142,0.5225937962532043,0.715783417224884,0.0027217579435127805,-0.004074145448687302,0.060185181442058186

+7.0037369,-0.012329771183431149,0.5244966149330139,0.7156752943992615,0.003844132147094384,-0.0047666133989142535,0.05963249640328839

+7.0115452,-0.012197524309158325,0.526140570640564,0.71576988697052,0.0037889558220242877,-0.005142654040225459,0.059620964904949766

+7.0222474,-0.01208923477679491,0.5278408527374268,0.7157525420188904,0.0047042161005886535,-0.005342906724832506,0.059448366110169605

+7.0320092,-0.011967957951128483,0.5293799638748169,0.7158169150352478,0.004701094512298413,-0.005252533871276243,0.0593319327749175

+7.0427426,-0.01186833344399929,0.5309485197067261,0.7156866788864136,0.004922341421904386,-0.005146909654630981,0.05914066808594266

+7.0534788,-0.011757878586649895,0.5323816537857056,0.7157317399978638,0.004887801499589088,-0.004911316652952276,0.059223084054092406

+7.0632386,-0.01165196392685175,0.5337560772895813,0.7157868146896362,0.004537128839958996,-0.0052649057348693705,0.058703230692286126

+7.073037,-0.011550777591764927,0.5350720882415771,0.7158504128456116,0.004537128839958996,-0.0052649057348693705,0.058703230692286126

+7.0817832,-0.01145470142364502,0.5363301634788513,0.7159249782562256,0.004200071359637315,-0.005815119880893275,0.0568995615666012

+7.092519,-0.011363941244781017,0.5375320315361023,0.7159954905509949,0.004200071359637315,-0.005815119880893275,0.0568995615666012

+7.1032549,-0.011278829537332058,0.5386791825294495,0.7160537838935852,0.003914605835266067,-0.006876948900627709,0.05523007920193569

+7.1130146,-0.009629921056330204,0.5380420088768005,0.713546633720398,0.0012894597490796396,-0.006324644576858732,0.05691202928450336

+7.1237513,-0.009510439820587635,0.5389478206634521,0.7134138345718384,0.0011299894327440286,-0.006369734913284488,0.056410341204866765

+7.1325346,-0.009217842482030392,0.5393036603927612,0.7125900983810425,-0.0014635431485452504,-0.00634724346824948,0.05645880384974253

+7.142331,-0.009108408354222775,0.5400631427764893,0.7124044299125671,-0.0015626241769097183,-0.006315688499840082,0.055734168862046705

+7.152054,-0.008768088184297085,0.5406737327575684,0.7119133472442627,-0.004283687884696532,-0.0059436734507046065,0.05509189367400734

+7.1627906,-0.00865909643471241,0.5413222908973694,0.7116967439651489,-0.0041332239979975155,-0.005559300663059041,0.05399731544273673

+7.1725871,-0.008487433195114136,0.5414548516273499,0.711565375328064,-0.00618475756317393,-0.005087582237529634,0.052378441572860056

+7.182335,-0.008369683288037777,0.5420640707015991,0.7113375067710876,-0.005996179718987589,-0.005419208552993642,0.05055059358601041

+7.1930785,-0.008150606416165829,0.5429039001464844,0.7111388444900513,-0.007963986681027279,-0.005625591120870615,0.04822624782593125

+7.2028069,-0.008029883727431297,0.5434340834617615,0.7109626531600952,-0.007729239843628154,-0.006426409372788333,0.046144398156433376

+7.2115913,-0.007842479273676872,0.5442856550216675,0.7108690738677979,-0.009565764186246504,-0.007140542226902457,0.043496581154119474

+7.2223265,-0.007720012683421373,0.5447511076927185,0.7107388973236084,-0.009332373732166058,-0.008140214205524653,0.04136775810958908

+7.233067,-0.007543543353676796,0.5456300973892212,0.7107346057891846,-0.010340031669300295,-0.008332593717106837,0.03903709508569328

+7.2418483,-0.007419990375638008,0.54604572057724,0.7106520533561707,-0.009947220895439441,-0.008553912544032566,0.03751311981467759

+7.2525841,-0.007249082438647747,0.5469217300415039,0.7106281518936157,-0.011273101916864179,-0.008247874478889094,0.03574954182730814

+7.263319,-0.006908676121383905,0.5482199192047119,0.7106158137321472,-0.010836227206786911,-0.008089932620619321,0.03487046594577866

+7.2732879,-0.006908676121383905,0.5482199192047119,0.7106158137321472,-0.01181321454184669,-0.007381373496419652,0.03346350707925756

+7.2838811,-0.009602520614862442,0.5540376901626587,0.7106270790100098,-0.009799924448766489,-0.00797522369252338,0.029406938536542415

+7.2916897,-0.009602520614862442,0.5540376901626587,0.7106270790100098,-0.010769245905091932,-0.007738928101919861,0.028763352071397606

+7.3043819,-0.009597850032150745,0.5556603074073792,0.7112851142883301,-0.009681320469920492,-0.007746814685979165,0.02729149506246685

+7.3122446,-0.009555508382618427,0.5561686158180237,0.7114212512969971,-0.010175907263010018,-0.008142874172537395,0.02681326637594994

+7.3239013,-0.009389963932335377,0.5567935705184937,0.711815595626831,-0.008396411070208535,-0.00845616132312137,0.026422759433451255

+7.3317051,-0.009359892457723618,0.5572481155395508,0.7119775414466858,-0.009057181655202477,-0.009066957669430584,0.026829062057005026

+7.3443988,-0.00933480728417635,0.5577542781829834,0.7121688723564148,-0.00842437752187657,-0.008975099082596609,0.02758187963820666

+7.3522646,-0.009325656108558178,0.5581552982330322,0.7123327255249023,-0.00808375101007148,-0.00852294950283918,0.028398499430377165

+7.3648891,-0.009384003467857838,0.5587452054023743,0.7124700546264648,-0.007468193303612135,-0.007818191127824024,0.029033370517751747

+7.3726989,-0.009397873654961586,0.5590915083885193,0.7126377820968628,-0.00717160386820386,-0.006955240417458049,0.02950640467813714

+7.3853853,-0.009483144618570805,0.5596103668212891,0.71274334192276,-0.006237291873801674,-0.006240012367920387,0.029755001378276986

+7.3922591,-0.009517460130155087,0.5598998069763184,0.7128970623016357,-0.005927626586886992,-0.0056239568500970945,0.029744569195462183

+7.4049061,-0.009677239693701267,0.5603649020195007,0.7130351662635803,-0.005517132485018588,-0.005169067917407521,0.0296287667647351

+7.411741,-0.00973193347454071,0.5605971217155457,0.7131731510162354,-0.0052833434024756945,-0.005026609829767154,0.02913359017191756

+7.425405,-0.00984257087111473,0.5610287189483643,0.7132726311683655,-0.005087676161205287,-0.005187739105354611,0.028466525613941543

+7.4322331,-0.009912962093949318,0.5612061619758606,0.7133638858795166,-0.004867211011983569,-0.0054315573894646915,0.02763367414694032

+7.4458971,-0.010051929391920567,0.561631977558136,0.7133604884147644,-0.004275405745532611,-0.005743765547153565,0.026814630070802033

+7.4527886,-0.01013950165361166,0.561758816242218,0.713428795337677,-0.003951150394521969,-0.005892109636942589,0.026258080499412716

+7.4634651,-0.010311529971659184,0.562335193157196,0.713525652885437,-0.004029420432253604,-0.005978770486254784,0.025672752981114884

+7.4742028,-0.010273837484419346,0.5637232065200806,0.7145253419876099,-0.0037935804298246134,-0.005921408340857358,0.025297204049940656

+7.4839615,-0.010590413585305214,0.5629021525382996,0.7136873602867126,-0.0034549393537886292,-0.005474243989978071,0.02485491944051957

+7.4947019,-0.010566513054072857,0.5641829967498779,0.7146361470222473,-0.003180618945979605,-0.004923459845758222,0.02456706492799708

+7.504457,-0.010866574943065643,0.5633479356765747,0.7137665152549744,-0.001586657613984608,-0.004092893140661447,0.02393526432472338

+7.5122699,-0.011005304753780365,0.5633445978164673,0.7137840986251831,-0.0027713321373087326,-0.0034635498175432135,0.02419661494370791

+7.5249531,-0.011183222755789757,0.56379234790802,0.7138360738754272,-0.0024523547806525473,-0.0028488869969837314,0.023921987959177535

+7.5347171,-0.011184710077941418,0.5651035904884338,0.714792788028717,-0.0022151957140083504,-0.0022106134901319087,0.02384567255843758

+7.54449,-0.011479293927550316,0.5641859173774719,0.7138782143592834,-0.001542430734195244,-0.0018723265761040394,0.023442833507514162

+7.5542331,-0.011495609767735004,0.5653939247131348,0.7148118615150452,-0.001463194766760607,-0.0014150289298545087,0.023060762088236188

+7.5649691,-0.011738606728613377,0.5644758939743042,0.7138991355895996,-0.001051914548426392,-0.0009580039340464753,0.02217864315729767

+7.5747339,-0.011744684539735317,0.565666139125824,0.7149147391319275,-0.0010085062946755766,-0.0005738447099970399,0.021161270944918608

+7.5844891,-0.012060550972819328,0.5646830797195435,0.7140673398971558,-0.0007456106403008045,-0.00021774757515014462,0.020058555424927377

+7.5923014,-0.012225423939526081,0.5645301342010498,0.7141188979148865,-0.0006753699490497833,0.0002800940370338705,0.019147809526784614

+7.604985,-0.012395131401717663,0.5648848414421082,0.7140239477157593,-0.0003898482659517418,0.0005529340553780703,0.018314712424509983

+7.612798,-0.012562877498567104,0.564705491065979,0.7140419483184814,-0.0003026714681851409,0.0009938645963440626,0.01785590577795093

+7.623689,-0.012717125937342644,0.5651479363441467,0.7140276432037354,-0.00021751102445330772,0.0012161707937912425,0.017345371834019022

+7.6334436,-0.012885126285254955,0.5649486780166626,0.7140160202980042,-0.0001933142508762163,0.001621511872665985,0.017073797483238833

+7.6441798,-0.013044292107224464,0.5652341842651367,0.7139703035354614,5.571880471162899e-05,0.0020434719247714337,0.016544769347191728

+7.6549181,-0.013068882748484612,0.5663983821868896,0.7149133086204529,3.0636332493756495e-05,0.002482980876431671,0.01594295660543857

+7.6646761,-0.01331762969493866,0.5653659105300903,0.7139354944229126,0.00021572536396699004,0.0029437697837698187,0.015307845520328014

+7.6744604,-0.013356799259781837,0.5664482712745667,0.7148107886314392,0.00015035735344900308,0.003306073264697679,0.014643119136007738

+7.6832196,-0.013606705702841282,0.5654201507568359,0.713881254196167,-1.1677203056046473e-05,0.0035895938401849935,0.01384012930509418

+7.6939597,-0.013627423904836178,0.5666055679321289,0.7148621678352356,-0.00017877668354193482,0.0037645740776851284,0.013325475261760499

+7.7037206,-0.013857238925993443,0.5655421018600464,0.7139113545417786,-0.00023681475745338226,0.004159074789090957,0.012746516332109527

+7.7144568,-0.013869332149624825,0.5667182207107544,0.7149253487586975,-0.0004448562119623729,0.004736574895299746,0.012440983033922982

+7.7243025,-0.01406511664390564,0.5656331181526184,0.7139485478401184,-0.0005011417772221124,0.005423885293633065,0.011904412872860794

+7.7330206,-0.014099236577749252,0.5667634606361389,0.7148661613464355,-0.0006326330757186016,0.005760010964369749,0.011325212259468264

+7.7437325,-0.014255394227802753,0.5656695365905762,0.7138192653656006,-0.0008725007468804767,0.005909790402582279,0.010662465671100305

+7.7544682,-0.014297185465693474,0.5669035911560059,0.7147327065467834,-0.0008726296089961367,0.005952981637336692,0.010386692278960365

+7.7632528,-0.014485742896795273,0.5657817125320435,0.7136821150779724,-0.0011913306814933158,0.00585133767937506,0.01000341004831845

+7.774295,-0.014511724933981895,0.5670172572135925,0.7145335674285889,-0.001247620511511242,0.005409862069956777,0.009942642069796205

+7.7847238,-0.014711971394717693,0.5658816695213318,0.7135090231895447,-0.0014358241195655637,0.005031989974674547,0.009788115852536595

+7.7935128,-0.01470772735774517,0.5669963955879211,0.7143588066101074,-0.0015150167867653782,0.004756368217338077,0.009793434164070457

+7.8032678,-0.014924838207662106,0.565886378288269,0.7133675217628479,-0.0014756774298840634,0.004720272943763559,0.009580970551174815

+7.8126137,-0.015024268068373203,0.5656058192253113,0.7133195996284485,-0.0014088152330520467,0.004798946657646265,0.009411495604239158

+7.8243894,-0.01514216884970665,0.5659342408180237,0.7132390141487122,-0.0012295658711502977,0.0050896014077634714,0.008924742523045304

+7.8339537,-0.015133021399378777,0.5671706795692444,0.7141261100769043,-0.0012877562078506238,0.0054029999680957844,0.008729674759005466

+7.8446963,-0.01529895793646574,0.5660845041275024,0.7131243944168091,-0.0012009029372843961,0.005793967319966813,0.008277696461689731

+7.853474,-0.015263119712471962,0.5672230124473572,0.7140041589736938,-0.0012585021314023516,0.006118832070655864,0.007955330298532261

+7.8632349,-0.015451755374670029,0.5660871863365173,0.7129786014556885,-0.0011859956263588214,0.006284435599461447,0.007350765435510032

+7.8729966,-0.01552675198763609,0.5658077597618103,0.7129318118095398,-0.0012141138737419195,0.006429319622189296,0.007084561459672571

+7.8827538,-0.015456036664545536,0.565221905708313,0.7121316194534302,-0.0023323044729275056,0.006855947840973099,0.0073495145495265125

+7.8935248,-0.015589604154229164,0.5670024752616882,0.7131410241127014,-0.002284450882772718,0.007040722520002605,0.007430500253058518

+7.9033014,-0.01572379283607006,0.5660977363586426,0.7121821641921997,-0.0022806384810794868,0.007241714983207641,0.0066049019808199225

+7.9140267,-0.01560357864946127,0.5672785639762878,0.7131170034408569,-0.001065721631796968,0.007727870586816515,0.006433357645983205

+7.9237759,-0.01573309116065502,0.5662702322006226,0.7120746970176697,-0.002094984656679743,0.007771734332294764,0.007136440098249832

+7.9354575,-0.015620418824255466,0.567281186580658,0.7128421664237976,-0.0014114604876343509,0.007966597989355988,0.006941388689322714

+7.9432805,-0.015788009390234947,0.5662497282028198,0.7118451595306396,-0.002568277066645074,0.007791742480073491,0.0073610143514364545

+7.9528985,-0.015677323564887047,0.5672827959060669,0.7125889658927917,-0.0026523417264244,0.007548235502916158,0.007413332331653971

+7.9626952,-0.015827050432562828,0.5662636160850525,0.7116013169288635,-0.0028193990027847618,0.007255936475104217,0.007562098229922118

+7.973291,-0.015697920694947243,0.5673510432243347,0.7124001383781433,-0.0026963598502660027,0.006800998620906249,0.007959429121889914

+7.9840255,-0.015843065455555916,0.566318690776825,0.7114138007164001,-0.002753142233645734,0.006274488650716233,0.00812464130363905

+7.9937909,-0.015683602541685104,0.5673707127571106,0.7122840285301208,-0.002690537370429594,0.006066846741834878,0.008500606336980118

+8.0028575,-0.015813423320651054,0.5662921667098999,0.7112858891487122,-0.002874318521768127,0.005881836318776855,0.0089397397512191

+8.0145325,-0.015700742602348328,0.5674723386764526,0.7120887637138367,-0.001771910388701791,0.006022441920250707,0.00885834229431517

+8.0233162,-0.015797430649399757,0.5664147138595581,0.711151659488678,-0.002899515885557052,0.006023617664672932,0.009477929757952785

+8.0340568,-0.015677059069275856,0.5675519704818726,0.711962878704071,-0.0018067783717977974,0.0063534768872389,0.00893153375220299

+8.0428398,-0.015728088095784187,0.5664642453193665,0.710949718952179,-0.002759869866342446,0.006468868690095542,0.009401963207163506

+8.0545439,-0.015599791891872883,0.5676274299621582,0.7117674350738525,-0.0012760139496733956,0.006451574530891773,0.008821381550458933

+8.063327,-0.015667876228690147,0.5664803981781006,0.7107356786727905,-0.00228006370674419,0.005577756062765369,0.009250101016634024

+8.0740685,-0.015528006479144096,0.5675744414329529,0.7115075588226318,-0.0009392982233361536,0.005167538849842941,0.008965079530281457

+8.0818763,-0.01561725977808237,0.5664770603179932,0.7105147242546082,-0.00219007537733427,0.004336240529851487,0.009516656996269888

+8.0945599,-0.015439983457326889,0.5675521492958069,0.7113495469093323,-0.0008516178265872579,0.003977881612848136,0.009101584119257815

+8.1025033,-0.015507924370467663,0.5664310455322266,0.7102943062782288,-0.002161543884049477,0.0035356877762227784,0.009732099750820433

+8.1142193,-0.015323485247790813,0.5675150156021118,0.7111328840255737,-0.0007449608641363792,0.0035050858693056897,0.00946568041802297

+8.1230037,-0.01532505452632904,0.5664191842079163,0.7100480198860168,-0.001982138591609923,0.003373718289697994,0.010095911740794558

+8.1337393,-0.015136812813580036,0.5672951340675354,0.7108004093170166,-0.0009467546717012648,0.0032986593392466904,0.009755950006574258

+8.1435042,-0.015135330148041248,0.5661801695823669,0.7097234725952148,-0.0021580323443729874,0.0029898784512861613,0.010280283705750423

+8.1532601,-0.014949356205761433,0.567151665687561,0.7105163335800171,-0.001979238662302149,0.002738417426115969,0.010472196778351251

+8.1620485,-0.014953656122088432,0.5660210251808167,0.7094765901565552,-0.0018863091618286946,0.0028702681333591575,0.010595657405592039

+8.1743382,-0.014771129004657269,0.5669766068458557,0.7102648019790649,-0.0006181550549990405,0.002818348576943088,0.009985224124378949

+8.1821467,-0.014801829122006893,0.5658179521560669,0.7092494964599609,-0.0015270890563781605,0.002469605113698131,0.0102050421064197

+8.1929093,-0.014673316851258278,0.5667092800140381,0.7098206281661987,-0.0006025420334265998,0.0023619347830117375,0.009352763159866084

+8.202675,-0.014654162339866161,0.5656432509422302,0.7088411450386047,-0.0015323110909300822,0.0018818804446572078,0.009380517707190984

+8.2143545,-0.01450160052627325,0.5665483474731445,0.7094653844833374,-0.0007149783447840519,0.0016286899372824762,0.00845228386533835

+8.2231384,-0.01448110118508339,0.5655266642570496,0.7085258364677429,-0.0016771469548295475,0.001085521829611833,0.008611838095707532

+8.2328988,-0.01431578490883112,0.566424548625946,0.7091607451438904,-0.0007459732960606269,0.0008754913098043113,0.008013693672384525

+8.2426596,-0.014334713108837605,0.5653563737869263,0.7081985473632812,-0.0017195343467761581,0.0007210600949861755,0.008483696505020871

+8.2543717,-0.0141204334795475,0.5664008855819702,0.7090516686439514,-4.1883888640951886e-05,0.0010226866835787547,0.00813384048111349

+8.2622119,-0.01416762638837099,0.5652490258216858,0.7080262303352356,-0.0006841542825261464,0.0010519693284580093,0.008976153126577962

+8.2744598,-0.014024442061781883,0.5661771297454834,0.708605945110321,0.0005627180666591898,0.001014124970399811,0.008910019692889458

+8.2831565,-0.01405564695596695,0.565055787563324,0.7076088786125183,-0.000393517211826135,0.0006687061858315016,0.009677060728719612

+8.2929403,-0.0138803506270051,0.5660178065299988,0.7083239555358887,0.0007111506564115047,0.0003755050396521699,0.009441920585540617

+8.3026758,-0.013926246203482151,0.5648934245109558,0.7073869705200195,-9.993851880805911e-05,-0.00012259424250849997,0.009929550158262667

+8.3143891,-0.013746954500675201,0.5658078789710999,0.7081537246704102,0.0012652669592841306,-5.6718957387484565e-05,0.009039884731441123

+8.3231729,-0.013766949065029621,0.5646399259567261,0.707149088382721,0.0008685690004848369,-0.0002767993301893145,0.008974124333466739

+8.3339078,-0.01357035432010889,0.5656312108039856,0.7080140709877014,0.002411690629385459,-0.0003197660284822377,0.0077738494165806

+8.3417176,-0.013564223423600197,0.5644695162773132,0.7069889307022095,0.0018566357176986615,-0.0007774477890824849,0.007735434905170762

+8.3534278,-0.013382859528064728,0.5652766227722168,0.7077187299728394,0.003099001640169546,-0.0009498392010524263,0.0070660518044194124

+8.3632217,-0.013412545435130596,0.564111590385437,0.706703245639801,0.0023363321032411335,-0.0013333570300019728,0.00755799071610105

+8.3739242,-0.01327157486230135,0.5649610757827759,0.7072938084602356,0.003437432598059375,-0.0010968721510090573,0.007227845740339596

+8.3827608,-0.01326875388622284,0.5638315677642822,0.7062444686889648,0.00259506430095486,-0.000954377273733953,0.007865899352011771

+8.393469,-0.013086444698274136,0.5646826028823853,0.7069342732429504,0.004025977587853816,-0.0007925454456491079,0.007374342789155441

+8.4032037,-0.01311327051371336,0.5635609030723572,0.7059317827224731,0.0035028406983952003,-0.000863324789322418,0.0077142036071053575

+8.4129906,-0.012920385226607323,0.5643611550331116,0.7066632509231567,0.005109544149800574,-0.0007875951116826756,0.00705830923449665

+8.4227485,-0.012992169708013535,0.5632002949714661,0.7057073712348938,0.004190730073587453,-0.0010006121297993387,0.007217205749069662

+8.4334594,-0.012842291966080666,0.5640459060668945,0.7063835859298706,0.005491825312158416,-0.0010611210613609401,0.0063893744101962075

+8.4432245,-0.012903996743261814,0.5628373026847839,0.7053998112678528,0.004560326627771216,-0.0011938935473219954,0.0065085780463245155

+8.4529794,-0.012739945203065872,0.5637251734733582,0.7061917781829834,0.005748901887660352,-0.0011104785959934092,0.0053639237837829505

+8.461768,-0.01280234381556511,0.5625301003456116,0.7052388787269592,0.004839595387554486,-0.0013153440147597054,0.005340721459451188

+8.4724999,-0.012681891210377216,0.5633693933486938,0.7058960199356079,0.006152114231945906,-0.0009000035231793589,0.0046016190123698885

+8.4822863,-0.012723547406494617,0.5621630549430847,0.7048752903938293,0.005222849787559089,-0.0007617477317527889,0.005226508485241359

+8.4929956,-0.012592652812600136,0.5630316138267517,0.7055639624595642,0.0064770748339872146,-0.00030786322705338544,0.005193282183322146

+8.5027558,-0.012621386907994747,0.5618547201156616,0.7045525908470154,0.005437372053010446,-0.00023429322822195625,0.00602663534830704

+8.5135192,-0.012471955269575119,0.5626000761985779,0.7052518725395203,0.006499040796510789,-0.00048160577955714954,0.0058236026513758385

+8.5232516,-0.012495238333940506,0.5614261031150818,0.704246461391449,0.0057735910622421565,-0.001041799629587562,0.006242427971832067

+8.5310615,-0.012463336810469627,0.5610487461090088,0.7041846513748169,0.006049609892722141,-0.0014051758120485055,0.0061434148370828265

+8.5417958,-0.01234256848692894,0.5603225231170654,0.7033770084381104,0.005141986637781129,-0.0016951636500788449,0.006120180038105249

+8.55352,-0.012347782962024212,0.5617585778236389,0.7042429447174072,0.006732457794278659,-0.001690736966233584,0.00431320905219744

+8.5632679,-0.012374300509691238,0.5607462525367737,0.7032669186592102,0.005391274117408568,-0.001988479035451406,0.004040913695216014

+8.5738797,-0.012151301838457584,0.561578094959259,0.7041444778442383,0.0070786676787739705,-0.0017832539381549724,0.0027606358248710885

+8.5826219,-0.012207443825900555,0.5604304075241089,0.7031003832817078,0.006068465613537585,-0.0019152996054952682,0.002532956021231983

+8.5914103,-0.011992909014225006,0.5610695481300354,0.7038723826408386,0.007094197960430176,-0.0015851603274129676,0.0018934828177213422

+8.6021684,-0.012028111144900322,0.559941828250885,0.7028343081474304,0.005806475584484119,-0.0013865112148454752,0.002335387116346005

+8.6128779,-0.011835508048534393,0.5606786012649536,0.7035818696022034,0.007259386618616503,-0.0007231382698424288,0.0023216203022149266

+8.6226389,-0.01191257406026125,0.5595088601112366,0.7025731205940247,0.006325777476415726,-0.0005656702589603161,0.0033136840183787086

+8.6333733,-0.011743498966097832,0.5602028369903564,0.7032670378684998,0.007527014913594522,-0.00043888682142769327,0.003491926199847337

+8.6422175,-0.011818867176771164,0.5590108036994934,0.7022645473480225,0.006851639096501866,-0.0007675313296245837,0.004395824491947522

+8.6528988,-0.011640560813248158,0.5597123503684998,0.7030544281005859,0.007980739647383087,-0.0011719823538562052,0.00430766664233654

+8.6626535,-0.011714888736605644,0.5585367679595947,0.7021149396896362,0.006819610895376852,-0.002076039148709182,0.004888937493956988

+8.6724183,-0.01159832812845707,0.5592320561408997,0.7027652859687805,0.008032291848225967,-0.002639557097451737,0.004355688064387965

+8.6821779,-0.011628950014710426,0.5580586194992065,0.7017983198165894,0.00647519507530574,-0.002920650693976523,0.004401707241889022

+8.6929142,-0.01151357963681221,0.5589016079902649,0.7025083303451538,0.007882115824392,-0.002832156026160809,0.0034626145668925153

+8.7017221,-0.011593594215810299,0.5577115416526794,0.7015556693077087,0.006608768728683322,-0.002880232173591122,0.003284181934535195

+8.712435,-0.011480840854346752,0.5584460496902466,0.7022162675857544,0.007778568758450314,-0.0024310445867760807,0.0023567710342679896

+8.7222119,-0.011593513190746307,0.5572439432144165,0.7012512683868408,0.006682513019712723,-0.002242855095192152,0.0021875510449413105

+8.7319536,-0.011488688178360462,0.5580708980560303,0.7019060850143433,0.007928569645855081,-0.0016482315553253,0.001291885949347497

+8.7417184,-0.011631827801465988,0.5568734407424927,0.7009427547454834,0.007047703289955857,-0.0013818240030281637,0.0013464828032521297

+8.7514739,-0.011514944024384022,0.5576697587966919,0.7016375660896301,0.00824283767631221,-0.000918029348623308,0.000655341593293569

+8.7622098,-0.011664950288832188,0.5565031170845032,0.700695276260376,0.007052649238811095,-0.0008697200366063566,0.0013146286269461191

+8.7719886,-0.011535135097801685,0.5573148727416992,0.7014514207839966,0.008422101746083419,-0.0005848307807906574,0.0012707308733043137

+8.7818055,-0.011654586531221867,0.5561460852622986,0.7004750967025757,0.007097233554038212,-0.0008250710019409788,0.0020281654829372667

+8.7915147,-0.011517815291881561,0.5567952990531921,0.7012199759483337,0.008447097260169624,-0.0007861493790517354,0.002089921094369579

+8.8022527,-0.011635195463895798,0.5556170344352722,0.7002879977226257,0.0073675058267321045,-0.0010273077214538666,0.002606703256572229

+8.8120234,-0.011513511650264263,0.556319534778595,0.7010750770568848,0.008381818551028016,-0.0009070713033847379,0.001993593445382164

+8.8217463,-0.011575219221413136,0.5551496744155884,0.7001040577888489,0.007273852509462068,-0.0009022557403655851,0.0019800198111769385

+8.8330707,-0.011489653959870338,0.5559021234512329,0.700814425945282,0.008191844067715167,-0.00043640177168414757,0.0009658474563464968

+8.8428304,-0.011535006575286388,0.5547549724578857,0.6998589634895325,0.007091622526263086,-0.00016954942097021259,0.0007031522280241465

+8.8525902,-0.011413303203880787,0.5554967522621155,0.700652003288269,0.008293694569278533,0.0004108007754025202,-0.0005690027758660393

+8.8623504,-0.011475714854896069,0.5543360114097595,0.6997097134590149,0.006869048439982431,0.0007564445464511129,-0.0007339144995868894

+8.8721062,-0.011362827382981777,0.5549829602241516,0.7004690170288086,0.007976329432925937,0.001450264742832079,-0.0013488690275078455

+8.8818698,-0.011377528309822083,0.5538590550422668,0.6995391249656677,0.006710784550105178,0.0020197016643331072,-0.0011729602072785398

+8.8906497,-0.011249695904552937,0.5545706152915955,0.700348436832428,0.008026666942786139,0.002994736527244682,-0.0013554193181258096

+8.9023664,-0.011292677372694016,0.5534180402755737,0.6994243860244751,0.006878370319388833,0.0035968382707243026,-0.0007389078714468304

+8.9121212,-0.011168657802045345,0.5541349649429321,0.7001886963844299,0.007953107711063546,0.004147424466168409,-0.0008939923800203297

+8.9219148,-0.011218867264688015,0.5529788732528687,0.6992638111114502,0.006889984539709207,0.004255294508054308,-0.000269502711871648

+8.9326328,-0.011095638386905193,0.5536938905715942,0.6999844908714294,0.007680013240443462,0.004712926557629016,-0.00041013742711830685

+8.9423825,-0.01114749163389206,0.5525705814361572,0.6990706920623779,0.006158975180243638,0.005010300807962763,-8.961492406966265e-05

+8.9521425,-0.011002971790730953,0.5533146262168884,0.6998104453086853,0.007248362547782218,0.005284030239722131,-0.0011603930603228405

+8.9619024,-0.011062984354794025,0.5521978735923767,0.6989080309867859,0.005760889273705854,0.00568293887928242,-0.0011820679450591993

+8.9716592,-0.010906530544161797,0.5529121160507202,0.6996380090713501,0.006877599581061,0.006636951970612102,-0.0018754996042672227

+8.9814184,-0.010915144346654415,0.5518289804458618,0.6987776160240173,0.0053404058025548614,0.007559265496583621,-0.0017192611415572552

+8.9921538,-0.010762045159935951,0.5525943636894226,0.6995188593864441,0.006261459572328652,0.008386560237647788,-0.0024346047392807654

+9.0019184,-0.010729464702308178,0.551548957824707,0.6986746788024902,0.004811443244630059,0.008981650746779963,-0.001955635472415645

+9.0116784,-0.0105476975440979,0.5522376298904419,0.6994487047195435,0.006009218839960102,0.009723387370220375,-0.0021482228287247798

+9.0214505,-0.010500486940145493,0.5511337518692017,0.6985750198364258,0.004894706706410024,0.010155962190436596,-0.0013741004908550396

+9.0311954,-0.010306274518370628,0.5518842935562134,0.6993591785430908,0.006229183387627473,0.01061596214060126,-0.0014185032128632492

+9.0419294,-0.010187273845076561,0.5508005619049072,0.6984314918518066,0.005022890635786227,0.010909936926722588,-0.0010986570843007873

+9.0516897,-0.009946967475116253,0.5514223575592041,0.6992172002792358,0.006317551305233369,0.01149761545799141,-0.0017333763458162385

+9.0624304,-0.00981337483972311,0.5503492951393127,0.6982877850532532,0.005197789344113962,0.012070358799813588,-0.0016410099630916504

+9.0712606,-0.009586244821548462,0.5511002540588379,0.6989474892616272,0.006568827452583575,0.012927949380324384,-0.002142741321024647

+9.0829216,-0.009473235346376896,0.5500354766845703,0.6980447173118591,0.005362528335456105,0.01374444696927174,-0.001900501840061472

+9.0917057,-0.009203145280480385,0.5508301258087158,0.6987559795379639,0.006594259528371545,0.014874857915263688,-0.002520304588410548

+9.1024463,-0.009083675220608711,0.5497377514839172,0.6978061199188232,0.005381344668167888,0.0159471559476708,-0.002158778627441445

+9.1112303,-0.008762147277593613,0.5505586862564087,0.6985657215118408,0.0065936027843697545,0.017297504394387087,-0.002410185098095085

+9.1229395,-0.008550605736672878,0.5495010018348694,0.6975483894348145,0.005315861381996527,0.018304031343124492,-0.0020762514861868207

+9.1317266,-0.008196020498871803,0.5502930879592896,0.6982329487800598,0.006610384495052972,0.019298603347958104,-0.002265992630919853

+9.1424584,-0.007996019907295704,0.5492194890975952,0.6972028017044067,0.005284129949012426,0.020055023695403025,-0.001702394884169293

+9.1512468,-0.0075702485628426075,0.550016462802887,0.6979465484619141,0.006578366605475449,0.0208325646017096,-0.0018956073608245205

+9.1619825,-0.00735528115183115,0.5489497184753418,0.6969192028045654,0.005571461950078187,0.02137182034368973,-0.0013201872574139417

+9.1717396,-0.006874937564134598,0.549727201461792,0.6976656913757324,0.007156715010859328,0.022342858867536834,-0.001710225589003904

+9.1815319,-0.006639344152063131,0.5486405491828918,0.6966383457183838,0.006211595862346221,0.02276714753981344,-0.0015750540719517755

+9.1912597,-0.006110178306698799,0.5493895411491394,0.6974122524261475,0.007581918248366698,0.023629369585887947,-0.0023669252787135186

+9.201998,-0.005697490181773901,0.5483308434486389,0.6963616013526917,0.006602611902981912,0.02432437460981152,-0.002511812090157066

+9.2117543,-0.005031227599829435,0.5490158200263977,0.6972132325172424,0.007898525415694259,0.02572392648761762,-0.0031515595347808836

+9.2224912,-0.004560860805213451,0.5479263663291931,0.6961278319358826,0.006482390595488671,0.027354822497870836,-0.003124572894372001

+9.2312786,-0.0039023589342832565,0.5486897230148315,0.6969693899154663,0.007624150944931828,0.02751412612393319,-0.003511099034206431

+9.2410338,-0.003408523043617606,0.5476629734039307,0.6959307193756104,0.0066748680884439705,0.030210576894844028,-0.003141631296446082

+9.2517736,-0.0027232603169977665,0.5485341548919678,0.6967042088508606,0.007811967093540137,0.030353218246915385,-0.003559251417741926

+9.2615344,-0.0021613920107483864,0.5474913716316223,0.6956374645233154,0.007111062427521173,0.03220184889210368,-0.002827563693645924

+9.2712948,-0.001370603684335947,0.5483656525611877,0.6965690851211548,0.0085297564389661,0.03237169209197748,-0.0032324517097092062

+9.2820304,-0.0008347631664946675,0.5472480058670044,0.6955361366271973,0.007291873029742447,0.03360748124583932,-0.0026488399763407475

+9.2917911,-1.4774501323699951e-05,0.548246443271637,0.6964114308357239,0.008599630246704423,0.03375335553271445,-0.003103342360931165

+9.3026258,0.0006393167423084378,0.5471659302711487,0.6953520178794861,0.007699399210139519,0.035234125703459775,-0.003195067267294189

+9.3123898,0.0015284251421689987,0.5481499433517456,0.6961956024169922,0.008678517531639545,0.03537974489139781,-0.003671129919641413

+9.3231318,0.002226956421509385,0.5470837950706482,0.6951424479484558,0.007696022238801677,0.036973367398242495,-0.004088011715357731

+9.3309371,0.003234150819480419,0.5479851365089417,0.6960775852203369,0.008928389139425593,0.03806880759520028,-0.004812575013199871

+9.3417026,0.004008154384791851,0.5469090342521667,0.6949530243873596,0.00799905172171417,0.039014926030583,-0.004500771534796454

+9.3514543,0.005081472918391228,0.5478131175041199,0.6958081722259521,0.008850583453427522,0.04054973073388485,-0.005038761832096644

+9.3622537,0.005936392117291689,0.5467920303344727,0.6947233080863953,0.007892274917457658,0.04146994791181632,-0.004609439140404381

+9.3709502,0.007090650498867035,0.5479305386543274,0.6956762075424194,0.009014751390896962,0.04164140424826101,-0.005105122876542878

+9.3816905,0.007969402708113194,0.5468670725822449,0.6946137547492981,0.008539089539694473,0.04352434098632133,-0.0038202241019472676

+9.3914464,0.009234040044248104,0.5479044914245605,0.6956175565719604,0.009733797647589967,0.043709490174723406,-0.004254187637103671

+9.4021865,0.010156972333788872,0.5468142628669739,0.6945815682411194,0.00862579397943209,0.04456313358847755,-0.002973377508936655

+9.4109662,0.011474418453872204,0.5478675961494446,0.6955122351646423,0.009394750792886425,0.044720814128602605,-0.0034502401064550868

+9.4207261,0.012536641210317612,0.5468294024467468,0.6944603323936462,0.008332985666078378,0.04498712149922558,-0.0028204018823829277

+9.4314621,0.013943876139819622,0.5479484796524048,0.6954160332679749,0.009626626119587244,0.04568285450775834,-0.0031742781845883485

+9.4412523,0.015070764347910881,0.5468799471855164,0.6943320035934448,0.008847646189422293,0.04690951963237326,-0.0027922854367599306

+9.4509819,0.01638587936758995,0.5467649102210999,0.694322407245636,0.008847646189422293,0.04690951963237326,-0.0027922854367599306

+9.4617226,0.017721913754940033,0.5462061166763306,0.6935779452323914,0.008380191263068498,0.04814617809766436,-0.0029155700570455377

+9.471484,0.019281331449747086,0.5478177666664124,0.6949900984764099,0.009213129685767235,0.04840668583643156,-0.0041731785663612735

+9.482219,0.020621806383132935,0.5469533801078796,0.6940186023712158,0.009156647986430209,0.04989058235409584,-0.0036512663984026206

+9.4910026,0.022296054288744926,0.5480441451072693,0.6949437856674194,0.009331272024687842,0.05003453506817994,-0.004212803313408859

+9.4997823,0.02367052063345909,0.547081470489502,0.6939647793769836,0.008576330572617785,0.0506781562189977,-0.003648483467194316

+9.5115307,0.025499660521745682,0.5483390688896179,0.6951341032981873,0.009835056763385574,0.05157910445147116,-0.0038583673413972656

+9.5212635,0.02697962522506714,0.5472692847251892,0.6940076947212219,0.009668406205659705,0.05250327173283539,-0.0029577053445272007

+9.5319926,0.028685789555311203,0.5472356677055359,0.694021999835968,0.009668406205659705,0.05250327173283539,-0.0029577053445272007

+9.5408083,0.030373767018318176,0.5466904640197754,0.6931674480438232,0.00901862326288486,0.05256226478571219,-0.0014889886459940934

+9.5505336,0.03231551870703697,0.5484628081321716,0.6945242285728455,0.010326032713240731,0.05278631067545354,-0.0026352348739981275

+9.5613038,0.03392598032951355,0.5475326776504517,0.6934212446212769,0.00980709452660085,0.05262660201851342,-0.0012577703409303923

+9.5710534,0.03608669713139534,0.5486489534378052,0.6945182681083679,0.010328614750704575,0.05282519597528979,-0.0017296633391838175

+9.5827612,0.03778485208749771,0.5476607084274292,0.6934112310409546,0.009394913384482981,0.0528630909479515,-0.0005610481891312252

+9.5905582,0.04004641994833946,0.5490677952766418,0.6946147084236145,0.011009575351886876,0.05304587892267603,-0.0009632750740754508

+9.6012875,0.04175569489598274,0.5479303002357483,0.6934013962745667,0.01010098940902783,0.05305509284387349,0.0006164094416441204

+9.611067,0.044104453176259995,0.5492608547210693,0.6945476531982422,0.011722063263054009,0.05322825768616341,0.0002484859514037819

+9.6208308,0.045877307653427124,0.5481033325195312,0.6933087110519409,0.010811010590184736,0.0532938688745417,0.0019575431924197364

+9.6315772,0.04833029583096504,0.549338698387146,0.6944429874420166,0.012402215787811742,0.05354633640449196,0.0022298777263413828

+9.6413042,0.05022750422358513,0.548185408115387,0.6931624412536621,0.011036901992452585,0.05335282369868213,0.0032500737378241065

+9.6510963,0.052740033715963364,0.549631655216217,0.6942427158355713,0.0121576167094244,0.053624113939099306,0.003233422899523482

+9.660854,0.05468674376606941,0.5484799146652222,0.6929900646209717,0.010816553327016507,0.05343567860767534,0.0038564431133932178

+9.6706344,0.05731680244207382,0.5498621463775635,0.6941063404083252,0.012631649843988572,0.05365706369572717,0.0036742790475122115

+9.6813181,0.05935576930642128,0.5486705303192139,0.6928042769432068,0.011583156671676422,0.05332440561266963,0.004153901886324467

+9.6920631,0.0620814748108387,0.5498104095458984,0.6938614249229431,0.012616966468325492,0.0535204926701608,0.0038680585711461405

+9.7008626,0.06424108892679214,0.5486997961997986,0.6926451325416565,0.011651982182551129,0.053172614912943,0.004567835089500278

+9.7106225,0.06705479323863983,0.5501018166542053,0.693790078163147,0.012529943699435305,0.05330598536859327,0.004088000409923311

+9.7213354,0.06930606812238693,0.5489635467529297,0.6925451755523682,0.011583349768025426,0.053137904696871824,0.004616642885567888

+9.7311197,0.07223927229642868,0.5504689812660217,0.6938139200210571,0.013137375322013783,0.053764717456343154,0.004219156546343557

+9.7418647,0.07451919466257095,0.5492334961891174,0.6925216317176819,0.012430237531029634,0.05397682043297992,0.00482201456268903

+9.7515913,0.07754892110824585,0.5506084561347961,0.6937963366508484,0.013415248621669564,0.05415902931904984,0.004282214162992352

+9.761374,0.07989295572042465,0.549377977848053,0.6925821304321289,0.012388014256852967,0.05386805759085277,0.005178019193194478

+9.770158,0.08299972862005234,0.5508660078048706,0.6938755512237549,0.013230208963017883,0.05404033712210715,0.0045962004702608215

+9.7809125,0.08548945188522339,0.5495815873146057,0.692532479763031,0.011696832415810605,0.05338041626047798,0.0051567009723816155

+9.790656,0.0887080579996109,0.5512206554412842,0.6939855813980103,0.013281393225394143,0.05355850020261939,0.004544194862442954

+9.8013671,0.09120726585388184,0.5498428344726562,0.6926289200782776,0.012021559467883873,0.052521821174206236,0.005363953964203691

+9.8111266,0.09423793107271194,0.549795389175415,0.6926496028900146,0.012021559467883873,0.052521821174206236,0.005363953964203691

+9.8218627,0.09709517657756805,0.5490753054618835,0.6916728019714355,0.01089467966767029,0.05110911602620904,0.006546266534099926

+9.8311339,0.10030175000429153,0.5511732697486877,0.6932336688041687,0.011843756945330708,0.051296180154399816,0.004955572467170003

+9.8408576,0.10303190350532532,0.5500985980033875,0.6921102404594421,0.010588914524585848,0.05043340916985487,0.005927603587368295

+9.8496676,0.10623639076948166,0.5500542521476746,0.6921447515487671,0.010748050143567053,0.05029050680398785,0.006238306318689969

+9.8613756,0.10930471867322922,0.5494881868362427,0.6913237571716309,0.00999474645500165,0.04935119066860679,0.00716173904056493

+9.871137,0.11259274929761887,0.5493856072425842,0.6912888884544373,0.00999474645500165,0.04935119066860679,0.00716173904056493

+9.8808706,0.11585808545351028,0.5489855408668518,0.6906856298446655,0.009259298352568814,0.04874816903254627,0.0078086044295915214

+9.8906587,0.11923523247241974,0.5488354563713074,0.6906211376190186,0.009259298352568814,0.04874816903254627,0.0078086044295915214

+9.9014102,0.12264746427536011,0.5485761761665344,0.690356969833374,0.00910115022006517,0.04798114152105623,0.007623814995874531

+9.9101756,0.1257806122303009,0.5517755150794983,0.6924397945404053,0.011233908741873811,0.04808094778265595,0.004637678703246366

+9.920914,0.12883369624614716,0.5509543418884277,0.691352128982544,0.010825786638672981,0.046694287950186875,0.004013983571872721

+9.9316474,0.13237342238426208,0.5509799122810364,0.6913442015647888,0.011048812855505364,0.04617577440041177,0.0035463677072608327

+9.9414081,0.13565678894519806,0.5505530834197998,0.6905589699745178,0.010224797149951205,0.045274773390956057,0.0036425390829804686

+9.9511813,0.139266237616539,0.5505354404449463,0.6904961466789246,0.01051022223644355,0.04452151383457706,0.003798201771209828

+9.9609306,0.14272667467594147,0.5502512454986572,0.6899681091308594,0.009168943590404086,0.043733157031554816,0.004599869108152031

+9.9716409,0.14640770852565765,0.5501976013183594,0.6898730993270874,0.009638677751413428,0.04294885276854598,0.004606298813421138

+9.9804475,0.1499820202589035,0.5499802827835083,0.6895705461502075,0.008411215251753286,0.0427759939184346,0.005548688604402931

+9.9902125,0.1537337750196457,0.549896776676178,0.689447283744812,0.00892719230164861,0.04220133746416555,0.006618634928226777

+10.000944,0.1574283242225647,0.5497227907180786,0.6893200874328613,0.007848265678098118,0.04116643770726591,0.00725725771172672

+10.0106791,0.16125117242336273,0.5496151447296143,0.6891686916351318,0.00828380280857433,0.04030422079606948,0.007394800215578388

+10.0204646,0.16502974927425385,0.549447774887085,0.6891571879386902,0.007171761349463871,0.03949242028365933,0.00720077434797678

+10.031202,0.16892291605472565,0.5493196845054626,0.6890246868133545,0.00775267626044767,0.038741712249042486,0.006543096000687838

+10.042888,0.17281480133533478,0.549180269241333,0.6890759468078613,0.007215617084346936,0.0378501469121936,0.005663209382313238

+10.0506962,0.1757073998451233,0.552837610244751,0.6912660598754883,0.01061572358865669,0.03670051194472651,0.0018564302661380385

+10.060479,0.1792193502187729,0.5523242950439453,0.6904205083847046,0.009813009103722585,0.03537806252780009,0.0012911738414153292

+10.0702424,0.18362416326999664,0.5541611909866333,0.6926653981208801,0.01239341459650681,0.03474806836979392,0.000166449391646166

+10.0809522,0.18692322075366974,0.5530174374580383,0.6913523077964783,0.011684267465865487,0.032939666722893814,0.00029118978841546846

+10.0907357,0.1913963109254837,0.5545111298561096,0.6932985782623291,0.014115133985289813,0.031787835262745937,0.000548502516942521

+10.1004977,0.19476792216300964,0.5532178282737732,0.6918012499809265,0.013604314187339083,0.029858886254390777,0.0015045017933236992

+10.1102556,0.19923479855060577,0.5547399520874023,0.6936089992523193,0.016275897847142024,0.028706903085237684,0.0024265139040496584

+10.1209912,0.2025790810585022,0.5533432960510254,0.69202721118927,0.015548330248452041,0.027144809796141554,0.003754356874362278

+10.1317037,0.2066894769668579,0.5534231662750244,0.6921338438987732,0.016044750567445584,0.025976131583837127,0.004842358779672761

+10.1405134,0.21036052703857422,0.5528156161308289,0.6910273432731628,0.015105942735849202,0.02462326077544454,0.006368947831050417

+10.1512237,0.2145000696182251,0.5528551340103149,0.6910718083381653,0.015504637399248324,0.023566170523306517,0.007235408717394041

+10.1610074,0.21828784048557281,0.5525186061859131,0.690288782119751,0.014706026006883099,0.022145831329544084,0.008171155727610756

+10.1707699,0.22292554378509521,0.5544878840446472,0.6927278637886047,0.017854275605792357,0.02004918254896984,0.00733462232650348

+10.1805036,0.22635215520858765,0.553425133228302,0.6913989782333374,0.01668978644918059,0.017902017994157304,0.007548782748648547

+10.1981043,0.23054134845733643,0.5534510016441345,0.6914448142051697,0.015826322925163443,0.013904610666780655,0.007457102544234133

+10.2010484,0.23424793779850006,0.5529444813728333,0.690548837184906,0.015826322925163443,0.013904610666780655,0.007457102544234133

+10.2117812,0.23844319581985474,0.5529224276542664,0.6905158758163452,0.016215040689682176,0.012038677049824557,0.007287375558945392

+10.2214969,0.24231405556201935,0.5526036620140076,0.6899411678314209,0.014791608222179061,0.00972441737879952,0.007721877731406597

+10.2303044,0.24701595306396484,0.554550051689148,0.6925156116485596,0.017511693019188874,0.010166445726843712,0.006265284521791322

+10.2410501,0.2509036660194397,0.553557276725769,0.6912336349487305,0.01648330103625006,0.007645849049864899,0.006873112467360031

+10.2508169,0.25510796904563904,0.5535405874252319,0.6912193894386292,0.017134617536336025,0.005493290274715743,0.007083532720111687

+10.2615451,0.2586551904678345,0.5529830455780029,0.6903463006019592,0.015997001934190635,0.0031706399441177907,0.007894587324304482

+10.2703206,0.2634396553039551,0.5547541975975037,0.6928989887237549,0.018865342086158577,0.002022291490177487,0.007205158299146365

+10.2804143,0.26253199577331543,0.5536006689071655,0.6914960741996765,0.01785983186720248,-0.0001773356419554457,0.0078959331440559

+10.2911175,0.26669076085090637,0.5535572171211243,0.6914975047111511,0.018286239239127124,-0.0013261646838671627,0.008145909597588782

+10.300912,0.2703109085559845,0.5530261993408203,0.6906529664993286,0.01707321100029726,-0.0027728630289040536,0.008912653387530846

+10.3116135,0.2750019133090973,0.5546645522117615,0.6929954290390015,0.019859332287485678,-0.003315490826527459,0.008169121528168382

+10.3204346,0.2784426212310791,0.5535351634025574,0.6915522813796997,0.01867399424297824,-0.004876583851146684,0.00863232585792897

+10.3311356,0.28255295753479004,0.5534552931785583,0.6915476322174072,0.018913262296580358,-0.005923210996373493,0.008357166435939143

+10.3399454,0.28623902797698975,0.5529028177261353,0.69059818983078,0.01753700532520853,-0.007228744469283296,0.00846514030244439

+10.3506539,0.2908867597579956,0.5545183420181274,0.6929230690002441,0.020075043879793513,-0.007956521050185699,0.007032733274873775

+10.3614142,0.29431989789009094,0.5534091591835022,0.6914759278297424,0.019036258926137233,-0.009799002563026706,0.007408994575865768

+10.3711507,0.29837241768836975,0.5532971620559692,0.6914623975753784,0.019166321966288764,-0.011213699198869305,0.007115926782889613

+10.3809347,0.30200865864753723,0.5527264475822449,0.6905322670936584,0.01759252197107971,-0.013127548104542756,0.007202316151939601

+10.3916781,0.3060159683227539,0.552564263343811,0.6904705762863159,0.01768481425764503,-0.01458750166329437,0.007070085304859229

+10.4004505,0.30977845191955566,0.5521774291992188,0.6899042129516602,0.016556594644608263,-0.016315795039118598,0.007383932799480974

+10.411166,0.31374040246009827,0.5519738793373108,0.6898176074028015,0.016622589757955608,-0.017723214096912118,0.007429645955626945

+10.4199748,0.31768563389778137,0.5517627000808716,0.6897389888763428,0.016669882588556766,-0.018979936216103326,0.007298980077858777

+10.4326736,0.32651078701019287,0.5532799363136292,0.692831814289093,0.019507529717160833,-0.0204970086545721,0.004238183040016303

+10.440447,0.32651078701019287,0.5532799363136292,0.692831814289093,0.019507529717160833,-0.0204970086545721,0.004238183040016303

+10.4521907,0.33481335639953613,0.553788959980011,0.694851279258728,0.021568794419770585,-0.02211931028928475,0.0023575449148003857

+10.4599656,0.33481335639953613,0.553788959980011,0.694851279258728,0.021568794419770585,-0.02211931028928475,0.0023575449148003857

+10.4726896,0.34278401732444763,0.5536341071128845,0.6961221098899841,0.0232168313252028,-0.025001222798837507,0.0020796493237057656

+10.4805207,0.34278401732444763,0.5536341071128845,0.6961221098899841,0.0232168313252028,-0.025001222798837507,0.0020796493237057656

+10.4932263,0.3505156338214874,0.5531830787658691,0.6968947052955627,0.024382536111786698,-0.028682119389942275,0.002965010499314789

+10.5009929,0.3505156338214874,0.5531830787658691,0.6968947052955627,0.024382536111786698,-0.028682119389942275,0.002965010499314789

+10.5098018,0.3543594181537628,0.5531080961227417,0.6973085403442383,0.023998038967642844,-0.030610423859719505,0.0034924643848923916

+10.5205369,0.35817426443099976,0.5530292987823486,0.6977207064628601,0.023635435196174077,-0.0325403758064469,0.004272756390061463

+10.5341771,0.3654792010784149,0.5524111390113831,0.6977149248123169,0.02544635398357713,-0.036778845061946314,0.006195661454046444

+10.5400573,0.3654792010784149,0.5524111390113831,0.6977149248123169,0.02544635398357713,-0.036778845061946314,0.006195661454046444

+10.5517463,0.3689899146556854,0.5519760847091675,0.697361171245575,0.02724710742091043,-0.03877870095532928,0.006838187577865084

+10.5605555,0.3726365566253662,0.5518369078636169,0.6975991129875183,0.0268131125298083,-0.04033987093544628,0.00692129349896036

+10.5722663,0.3754993975162506,0.5506588220596313,0.6960194706916809,0.06801111800237765,-0.042992346772801275,0.00654638704268296

+10.5810512,0.37901535630226135,0.5504922270774841,0.6960208415985107,0.06744137310684753,-0.04434088869116121,0.006068328571823566

+10.5907846,0.3824901580810547,0.5503168106079102,0.6959956288337708,0.06682255576401173,-0.04567509073210487,0.005465485486459732

+10.6005693,0.3859221935272217,0.5501329898834229,0.6959500908851624,0.06526896606567965,-0.04697306226738406,0.004851564522930897

+10.6122832,0.3893100917339325,0.5499413013458252,0.6958850026130676,0.06352795887402728,-0.04834828877773167,0.004277061836272178

+10.6249453,0.39265260100364685,0.5497423410415649,0.6957988142967224,0.061727556344725314,-0.04952751275533829,0.00372489067203492

+10.6308026,0.3959485590457916,0.5495367050170898,0.69568932056427,0.05998674694597833,-0.05077571518743207,0.0033921517165743527

+10.6405738,0.39919722080230713,0.5493248701095581,0.6955478191375732,0.058207812378578215,-0.05183399953746654,0.0030756841333231953

+10.6503224,0.40239760279655457,0.5491071939468384,0.6953710317611694,0.05644476149881995,-0.05259382850928318,0.002852934729169667

+10.6610683,0.40554845333099365,0.5488839149475098,0.6951664686203003,0.05479820464174244,-0.053177404043454016,0.002739632589222527

+10.6708459,0.40864861011505127,0.5486552119255066,0.6949426531791687,0.05321889266259951,-0.05368494041686296,0.0024765546778671554

+10.6796334,0.4116969108581543,0.5484212040901184,0.6947113871574402,0.05167554720533353,-0.05435241929953593,0.0020498049912042217

+10.6903387,0.4146921634674072,0.5481823086738586,0.6944836974143982,0.05012610155267021,-0.05520276354999079,0.0015662063253994638

+10.7000985,0.4176335632801056,0.5479389429092407,0.6942601799964905,0.04851158702020818,-0.05592387651782318,0.0008817202354539012

+10.7108649,0.42052075266838074,0.547691822052002,0.6940322518348694,0.046940194004294285,-0.056796630148617654,0.00020279152143675273

+10.7205938,0.42335307598114014,0.5474416017532349,0.6937974095344543,0.04548557825128441,-0.05771950367371009,-0.00043841698537635333

+10.7303573,0.42612966895103455,0.5471889972686768,0.6935549974441528,0.04414907377332776,-0.058511123015153765,-0.0008782875314671743

+10.7401357,0.4288499057292938,0.5469346046447754,0.6933006644248962,0.04280282754162684,-0.0592390991588282,-0.0012860932501799391

+10.7508736,0.4315132200717926,0.5466788411140442,0.6930316090583801,0.041464331169311176,-0.05977613138501542,-0.0017189874497163047

+10.7606083,0.4341185986995697,0.5464221835136414,0.6927536129951477,0.04011386744828932,-0.059971509731348106,-0.0020348498946661073

+10.7693936,0.4366649091243744,0.5461650490760803,0.6924795508384705,0.03877327401782329,-0.06006354533337072,-0.0022231675480496246

+10.7811207,0.4351184666156769,0.5411369800567627,0.6842869520187378,0.03138658641484245,-0.062443057284684814,0.0009620582828954381

+10.7899256,0.4373847246170044,0.5406157970428467,0.6836336851119995,0.0300893582006573,-0.0625690755387434,0.0004843924458463742

+10.8016117,0.4397881329059601,0.5396534204483032,0.6825752258300781,0.023070158708237413,-0.062403372209367626,0.0003835787766445156

+10.8103942,0.44193726778030396,0.5391066670417786,0.6818755865097046,0.022258829780318026,-0.062369866337409124,-0.0006049085296737462

+10.8191801,0.4442502558231354,0.538532555103302,0.6811937093734741,0.016760071589051094,-0.0618356804073402,-0.0016986938184840124

+10.8318667,0.44454169273376465,0.5420039296150208,0.6811826229095459,0.017444682286552136,-0.06134519542715784,-0.005513946153107418

+10.8406504,0.44653865694999695,0.5414533615112305,0.6798719763755798,0.012627006281996811,-0.06047226605440531,-0.006829242670198473

+10.8513857,0.4486040771007538,0.5410584807395935,0.6791567802429199,0.012437433193970542,-0.05926817089061196,-0.008798913152237827

+10.8611455,0.4504842460155487,0.5406760573387146,0.6783891916275024,0.007527670059242568,-0.05790322534907921,-0.010306692629759006

+10.8699308,0.45224159955978394,0.5403320789337158,0.6777768731117249,0.007421457661862684,-0.05666595142642739,-0.01158232222079921

+10.8816498,0.45409977436065674,0.5400264263153076,0.6772860884666443,0.0038170904497901777,-0.055646829339905064,-0.012438675075726229

+10.8914093,0.45642220973968506,0.5406617522239685,0.6790761351585388,0.00587868647777897,-0.05425277240311386,-0.01360818745907622

+10.9001933,0.457894891500473,0.5400628447532654,0.677905797958374,0.0019466847358767167,-0.05333721726192335,-0.013142744132211713

+10.9099537,0.45945093035697937,0.5398059487342834,0.6774988770484924,0.002203943578708609,-0.052293356839397,-0.012700770052065467

+10.9206887,0.4610055387020111,0.5394940376281738,0.6768429279327393,-0.00100924388033444,-0.05134995018027425,-0.01184692700209967

+10.9304653,0.46245643496513367,0.5392587780952454,0.6764876842498779,-0.0007124719065336879,-0.05044945363104663,-0.011177820765559753

+10.9402103,0.4640037715435028,0.539032518863678,0.6760945320129395,-0.0036783992835785683,-0.04944724515869451,-0.01079998440723157

+10.9509643,0.4662242829799652,0.5394164323806763,0.6782873272895813,-0.0015354175418725166,-0.048049969572079375,-0.011341270984795288

+10.9607486,0.4675004482269287,0.538859486579895,0.6772692799568176,-0.004010658958228046,-0.04751558759421183,-0.011365818973593903

+10.9706495,0.46878117322921753,0.538685142993927,0.6771518588066101,-0.003467891442066454,-0.046474219761208156,-0.01167045356611983

+10.9811118,0.47017911076545715,0.5384215712547302,0.6766062378883362,-0.005786744805487309,-0.045516731881508773,-0.01185622352320649

+10.989923,0.47220170497894287,0.5389313101768494,0.6788641214370728,-0.0029538531222608,-0.0440732172016268,-0.012532028601375702

+11.0006332,0.47320127487182617,0.538282573223114,0.6778131127357483,-0.00457120445512334,-0.04345145269322894,-0.012386674767848693

+11.0103931,0.47495681047439575,0.5387691855430603,0.6797561645507812,-0.002254098728444317,-0.0422284188089045,-0.012453339939831604

+11.0201514,0.4758910834789276,0.5379884839057922,0.6785442233085632,-0.004132300021255961,-0.04157147537259276,-0.011820628627031244

+11.0308874,0.4775124192237854,0.5385535359382629,0.6804327368736267,-0.0019069389958718526,-0.04078431543250792,-0.011428694763400544

+11.0406481,0.4784019887447357,0.5377691984176636,0.6792216300964355,-0.003478002308471393,-0.04039139563932321,-0.010590403118833514

+11.0504196,0.4793754816055298,0.5376781821250916,0.6793737411499023,-0.002998960718887315,-0.03988966450144282,-0.01009598637134977

+11.0601697,0.4804690182209015,0.5373820662498474,0.6787354350090027,-0.005265511356730792,-0.039352736032746236,-0.009595258994250221

+11.0699599,0.4813673496246338,0.5373006463050842,0.6788754463195801,-0.004881708577048524,-0.038656790971501806,-0.009493577277277123

+11.0802631,0.48253729939460754,0.53717440366745,0.6786006689071655,-0.006894336621807775,-0.03766079617649941,-0.009484640916052308

+11.0899935,0.48419857025146484,0.537651538848877,0.6809710264205933,-0.004912188245725913,-0.03611704012050054,-0.010105122123337033

+11.1009496,0.48502716422080994,0.5371996760368347,0.6801882982254028,-0.006523513148251922,-0.03523457253497149,-0.009870504499611285

+11.1111463,0.4864892065525055,0.5378012657165527,0.6823939085006714,-0.0039055715057473013,-0.03378707377432728,-0.010205146052842265

+11.1199297,0.4871767461299896,0.5371237397193909,0.6812841892242432,-0.005690168801632741,-0.03307607322828867,-0.010005108786364871

+11.1287101,0.488477885723114,0.5376483201980591,0.6832181215286255,-0.0036506393260506056,-0.03197804629878236,-0.01023858825766873

+11.1394463,0.48915988206863403,0.5369390249252319,0.6820257306098938,-0.005060048429903703,-0.031656946278652266,-0.009652800276327854

+11.150181,0.4904002547264099,0.5375574827194214,0.6839475035667419,-0.0023474356300228786,-0.03097299849627337,-0.009416318339566167

+11.1589666,0.49097344279289246,0.5368227958679199,0.6826801300048828,-0.0033742376421073556,-0.030819370020723012,-0.008554559400534132

+11.1697058,0.4922225773334503,0.5374521613121033,0.6845573782920837,-0.0008888690443619383,-0.03019250866352815,-0.008196849672163758

+11.1804697,0.49277999997138977,0.5367316007614136,0.6832121014595032,-0.002268683737936484,-0.030391879175245533,-0.007474572557218787

+11.1911723,0.4939190447330475,0.5373476147651672,0.6850536465644836,8.084407075696787e-05,-0.03010898683906088,-0.0074412717529298

+11.1989813,0.49450352787971497,0.536670982837677,0.6837369203567505,-0.001489296584460665,-0.03033773597114652,-0.006936128425457895

+11.2097175,0.49558424949645996,0.5372952222824097,0.6855267286300659,0.0005867651240432663,-0.030091845195783323,-0.006826607809266607

+11.2194787,0.49612078070640564,0.5365978479385376,0.6841246485710144,-0.0008764397130107989,-0.03003093314889035,-0.006263811176163131

+11.2302135,0.4971548914909363,0.5372538566589355,0.6858886480331421,0.0011779771921351615,-0.029403277556175784,-0.006580783716803425

+11.2399736,0.4976436495780945,0.5365607738494873,0.6844391226768494,-9.919282695126813e-05,-0.02903565448870671,-0.0063686725243197115

+11.2507339,0.4986495077610016,0.5371978282928467,0.6861920356750488,0.002126865834787699,-0.02802748581638438,-0.00661278793054727

+11.2595188,0.49908560514450073,0.5365291833877563,0.684766948223114,0.0009407932604090139,-0.02758124833331585,-0.006283429912541125

+11.2712133,0.49999406933784485,0.5372093915939331,0.6863299608230591,0.0028805527456734897,-0.026850190762781105,-0.006556540174375043

+11.2800758,0.5004271864891052,0.536555290222168,0.6848577857017517,0.0017037253995900975,-0.026679545768226804,-0.0060785080497072624

+11.2897761,0.5013419389724731,0.5371443629264832,0.6864838600158691,0.0035704031518342637,-0.026305369585560505,-0.00605433378695323

+11.30051,0.5016890168190002,0.5364847779273987,0.6849836707115173,0.0026049597325071274,-0.026259254129979512,-0.005366046882754776

+11.3102663,0.5025415420532227,0.5371072292327881,0.6864959001541138,0.004244728999399077,-0.025759431163883253,-0.0055378711337966385

+11.320005,0.5028486847877502,0.536454439163208,0.6849715709686279,0.0028423127024824403,-0.025838775122085815,-0.00488772123071565

+11.3297701,0.5031580328941345,0.5364809036254883,0.6848848462104797,0.0030383094632299014,-0.025732715132133682,-0.004552204870613626

+11.3395251,0.5037770867347717,0.5363314747810364,0.6839917302131653,0.0012246331672504083,-0.025504455231609876,-0.004089410740441076

+11.3502616,0.5047488808631897,0.5368713140487671,0.6857701539993286,0.00284518296338081,-0.025186431184661157,-0.004305089086833081

+11.3601681,0.5051267743110657,0.5364482998847961,0.6844561696052551,0.0014560428255639029,-0.025399602034514582,-0.003914711570797376

+11.3697814,0.5060035586357117,0.5369216799736023,0.6860695481300354,0.0035160396343335894,-0.02481315762074476,-0.0041777616128701725

+11.3795413,0.5061925053596497,0.5363446474075317,0.6845842599868774,0.002528172682129652,-0.02488243180491972,-0.003937776265770255

+11.391258,0.5069515109062195,0.53701251745224,0.6860549449920654,0.0041271824818957395,-0.024476508868121354,-0.0041227603325150715

+11.4010578,0.5071852207183838,0.5364177823066711,0.6844892501831055,0.0033146775790248717,-0.02430092465406777,-0.003809341201516954

+11.410779,0.5079126358032227,0.5370422005653381,0.6859510540962219,0.005055552233535947,-0.02374705169236056,-0.0037758773970244523

+11.4195577,0.5082049369812012,0.536445677280426,0.6843277215957642,0.004319433872444498,-0.02336562360475083,-0.0032638961566596983

+11.4312695,0.508901059627533,0.5369694232940674,0.6857367157936096,0.005781051689038259,-0.02280039888648098,-0.003366404533040427

+11.441034,0.5090621709823608,0.5363523960113525,0.6841336488723755,0.005086017265834021,-0.02288961048305582,-0.003175941976913667

+11.4498179,0.5091972947120667,0.5363776683807373,0.6839337944984436,0.005002955683299403,-0.022909551042820494,-0.003363166600385643

+11.4605488,0.5095862746238708,0.5362111926078796,0.6829614043235779,0.003746414306589293,-0.022914836198911905,-0.00323061920564687

+11.4703139,0.510352611541748,0.5368212461471558,0.6846798062324524,0.005351427546252868,-0.022707372226130187,-0.003722023758836586

+11.4800706,0.5104560852050781,0.5363773703575134,0.6834022998809814,0.004404489124041219,-0.022883612973400067,-0.0032146072680268095

+11.4898297,0.5111098885536194,0.5369338393211365,0.6849533915519714,0.005721131677150229,-0.02236642879712243,-0.0033076328345558403

+11.4995891,0.5112774968147278,0.5363805890083313,0.6835048794746399,0.004320476628324459,-0.021897541255781312,-0.0029607781146070095

+11.5113052,0.5118381381034851,0.5369812846183777,0.6849791407585144,0.0058035063056604205,-0.021093312488829334,-0.003154899248706671

+11.5210664,0.5119667649269104,0.5363591909408569,0.6834297776222229,0.004771670703332496,-0.020616597901200778,-0.0032184619189840336

+11.5298638,0.5119998455047607,0.5363869667053223,0.6833524703979492,0.0046338321013693635,-0.020382327103163702,-0.0037574926542895334

+11.540586,0.512300431728363,0.5361782312393188,0.6823398470878601,0.0037292277317433633,-0.020203187497339674,-0.003996266083547963

+11.5493651,0.5128698945045471,0.5368271470069885,0.6839181780815125,0.005043165560509045,-0.019886843145212295,-0.004663163972621404

+11.5601057,0.5130234360694885,0.5363754630088806,0.6826052665710449,0.00430228912717589,-0.019999652163982425,-0.004380837653310741

+11.5698661,0.5135343670845032,0.5369623303413391,0.6841298341751099,0.005409630115632345,-0.019953376116429056,-0.004500242917945865

+11.5806016,0.5136029124259949,0.5363830327987671,0.6826996803283691,0.004821323006271171,-0.02008725771656105,-0.003981685139633996

+11.590357,0.5140215158462524,0.5370144844055176,0.6841201186180115,0.0058190206130714454,-0.019880256501232138,-0.0040536643429473955

+11.6010989,0.5140451192855835,0.5363874435424805,0.6826347708702087,0.004982257603157298,-0.019935671819222796,-0.0036966310258254747

+11.6098793,0.5144183039665222,0.5370463728904724,0.6839878559112549,0.006225589951641196,-0.019656239331963005,-0.0038325270136700925

+11.6206867,0.5143621563911438,0.5371021032333374,0.6840408444404602,0.0059402475968975375,-0.01961233007098087,-0.0036964051603363348

+11.6303802,0.5145108103752136,0.5374035835266113,0.6849449872970581,0.00715589136712016,-0.019337735406664735,-0.0036823965417463493

+11.6391601,0.5147842168807983,0.5364566445350647,0.6828328967094421,0.005640119779436081,-0.019282735999250025,-0.0030267737828520106

+11.649893,0.5150104761123657,0.5371034741401672,0.6838993430137634,0.006698040661833942,-0.018939455096385244,-0.0032550871525222585

+11.6596528,0.5150526762008667,0.5363840460777283,0.6820952892303467,0.00484923695099366,-0.018859180048785434,-0.002852337047477706

+11.6703889,0.5153434872627258,0.5370460152626038,0.6832781434059143,0.005920999292806914,-0.0183001881031767,-0.003131710192019303

+11.6801496,0.5152802467346191,0.5364010334014893,0.6816226243972778,0.004491717753453668,-0.01802805509974815,-0.0028721497545743354

+11.6899098,0.5155801773071289,0.537050187587738,0.6828455328941345,0.005472247766257265,-0.017637882969800234,-0.003147138874566984

+11.6996693,0.5154531002044678,0.5364211201667786,0.6812370419502258,0.004134244540181949,-0.01767405029756892,-0.0027893143643852297

+11.7104361,0.5156955122947693,0.5371178388595581,0.6823909878730774,0.0052223715445846326,-0.01749531935121018,-0.002976297116994557

+11.7192223,0.5155670642852783,0.5364838242530823,0.6807330846786499,0.0037267324294580507,-0.01770309859588828,-0.0026102768224956748

+11.7299642,0.5158227682113647,0.5371530055999756,0.6819108724594116,0.004831085938149588,-0.017604379334590407,-0.002857340680424097

+11.7406942,0.5156396627426147,0.5365431308746338,0.6803172826766968,0.0037625332321015934,-0.017728832873955314,-0.002717519940683589

+11.7485028,0.5154411792755127,0.5365673303604126,0.6801016926765442,0.0036670353206023644,-0.01783654795712258,-0.0027441890011442043

+11.7602191,0.5154388546943665,0.5363792181015015,0.6790392398834229,0.0025354325052797176,-0.017836728231682236,-0.0025216098374656183

+11.7699743,0.515729546546936,0.5370839834213257,0.6803615689277649,0.003408306226705141,-0.017838781509960093,-0.002648943015895893

+11.780715,0.5154551863670349,0.5365915894508362,0.6789131164550781,0.0025697338320952497,-0.01788664009170928,-0.0020638026702495004

+11.789499,0.5151968598365784,0.5366091728210449,0.6787129044532776,0.00246671549448742,-0.01775348786687908,-0.001883986216131739

+11.8002303,0.515205442905426,0.5364614129066467,0.6777744889259338,0.0015054595335472639,-0.017317096604467837,-0.0016976694092602415

+11.8099906,0.5154686570167542,0.5371776819229126,0.6793032288551331,0.003218829803931165,-0.016568719137154696,-0.002467129120074621

+11.8207268,0.5153035521507263,0.5367625951766968,0.6779894232749939,0.0024938181098565,-0.01620760396244442,-0.0025274459145881627

+11.8304867,0.5155413150787354,0.5373566746711731,0.6794514656066895,0.00380896690389265,-0.0156106710235072,-0.003171599814722392

+11.840247,0.5152916312217712,0.5368098616600037,0.677939236164093,0.0025731869294466267,-0.015372883200763715,-0.0032256963806466597

+11.8519827,0.5154573917388916,0.5374470949172974,0.6792411804199219,0.0037847367684294506,-0.014508198829145625,-0.003598201604361773

+11.8597935,0.5151996612548828,0.5368586182594299,0.6776257157325745,0.003214041996952056,-0.01429450056523676,-0.003181663951656729

+11.8695549,0.5153453946113586,0.5375339984893799,0.6789128184318542,0.004687055095602967,-0.014046350842533938,-0.003425305363415323

+11.8793135,0.5149795413017273,0.5369390845298767,0.6773697733879089,0.004166592243358984,-0.013948572476625577,-0.0030444669650730133

+11.8909988,0.515108585357666,0.5375937223434448,0.6786835193634033,0.005068250662655036,-0.013337069602207274,-0.0030779610208794238

+11.8997827,0.5147378444671631,0.5369970202445984,0.6771513819694519,0.0035381070183537404,-0.013199512054902052,-0.0024269904771795276

+11.9095422,0.514851450920105,0.5376262664794922,0.6784830689430237,0.004208802796077509,-0.012679726260173748,-0.002251938069439331

+11.9202829,0.514462947845459,0.5370368361473083,0.6770310997962952,0.0030379169010476812,-0.012515902247907006,-0.0016348110791199342

+11.930043,0.5145527720451355,0.5377008318901062,0.6784239411354065,0.0038498465939936217,-0.012229158505603766,-0.0016006834554753947

+11.9399475,0.5142066478729248,0.5371032357215881,0.6769816875457764,0.0026738449161978484,-0.012100725196015587,-0.0011402516049716011

+11.9496016,0.5142722129821777,0.5377797484397888,0.6783856749534607,0.0037080030603798366,-0.011592805770467401,-0.001631553531130698

+11.9603385,0.5139479637145996,0.5371507406234741,0.6768803000450134,0.002548307336578414,-0.011541965567960874,-0.0018905948630471513

+11.9701299,0.5139761567115784,0.5379321575164795,0.6782500147819519,0.0038616860076039154,-0.010982794696553914,-0.0028916392004349873

+11.9798575,0.513651967048645,0.537298858165741,0.6767203211784363,0.002572906063017176,-0.010757683559720033,-0.0029705186655387176

+11.9905927,0.5136895179748535,0.5380426645278931,0.6781250238418579,0.003702940177750183,-0.010222773689914115,-0.0036466933307815093

+12.0003531,0.5132327675819397,0.5374009013175964,0.6766600012779236,0.00249514589891916,-0.010096686171967384,-0.0036868880989862503

+12.0101176,0.5132578611373901,0.5382256507873535,0.6780813336372375,0.00323530998744734,-0.009552924861358178,-0.00406995330162037

+12.0198734,0.5128459334373474,0.5375967025756836,0.6765919923782349,0.0021732161783650917,-0.009128534902075205,-0.0035514272811776925

+12.0296331,0.5128907561302185,0.5383853316307068,0.6780755519866943,0.0030239336063779937,-0.008287898582257331,-0.0035421215876923423

+12.0403697,0.5124781131744385,0.5377573370933533,0.6765850782394409,0.0019102188940989737,-0.007747843978066191,-0.002962886506570831

+12.0501303,0.512517511844635,0.5385143160820007,0.6780611276626587,0.002766063711863916,-0.006908484416327798,-0.0030281282893734663

+12.0599134,0.51213538646698,0.5379347801208496,0.6766636967658997,0.0016424623931421585,-0.006585095313906297,-0.002585722373874527

+12.069659,0.512157678604126,0.5386632084846497,0.6781108379364014,0.0026670820049985687,-0.006222748793395359,-0.0029806200419349917

+12.0803851,0.5117955207824707,0.5380550622940063,0.6766558289527893,0.001377107694509347,-0.006235493835323926,-0.0026707464011224685

+12.0901812,0.5118401646614075,0.538835883140564,0.6782069206237793,0.0020352570407979865,-0.006032145438775764,-0.002962536148417374

+12.0999379,0.5114516019821167,0.5382186770439148,0.6767962574958801,0.000873364006348756,-0.006264196328311305,-0.002400113660242544

+12.1096974,0.5114356875419617,0.5389763116836548,0.6782110929489136,0.0013514913156344286,-0.006279846950408758,-0.0027459331393807434

+12.1194261,0.5110540986061096,0.538349986076355,0.6767622828483582,-8.60164649081789e-05,-0.006958264594291389,-0.0025180289304632406

+12.1301617,0.5110429525375366,0.539137065410614,0.6781792640686035,0.000304346220024184,-0.006807715675328794,-0.0030812201180956964

+12.1399214,0.5106338858604431,0.5385226011276245,0.6767517924308777,-0.0006356760638461499,-0.006700100914137845,-0.002832360453711715

+12.1487055,0.5106109976768494,0.5393462181091309,0.6781076788902283,6.0891335361785e-06,-0.006115392292791022,-0.0032460309327593585

+12.1604175,0.5101491808891296,0.5387312769889832,0.676645040512085,-0.0009590918284618235,-0.00579665258674285,-0.002693709664046998

+12.1692346,0.5101439952850342,0.5395814180374146,0.6780108213424683,-9.576396962975332e-05,-0.004665380234187303,-0.00262543036892974

+12.1799369,0.5097330212593079,0.5390101671218872,0.6765688061714172,-0.00092727786118016,-0.004757610718114571,-0.0022716987733797126

+12.1896973,0.5097399353981018,0.5398085713386536,0.6779316067695618,0.00013454260815009956,-0.003992396776847371,-0.002289644569384053

+12.1994571,0.5092952847480774,0.5391754508018494,0.6763567924499512,-0.000561561030433964,-0.0037138558229669483,-0.0018687650070271524

+12.2101974,0.5092887878417969,0.5400448441505432,0.6776919960975647,0.00023988660758553036,-0.0032409509840688284,-0.0022885037535579035

+12.2199531,0.5089110732078552,0.5394803285598755,0.676216185092926,-0.001100194652128974,-0.0030668240828702047,-0.001892146317247384

+12.2297132,0.5089151263237,0.5402604937553406,0.6775321960449219,-0.0004310449164477256,-0.002883632189797893,-0.001989011020889984

+12.2384985,0.5084546804428101,0.539660632610321,0.676059901714325,-0.0011115517503880374,-0.003257068234942283,-0.0015188706596926075

+12.2492331,0.5084700584411621,0.5404655337333679,0.6774410605430603,-0.0006605233127324918,-0.003135519599358291,-0.0015008384045972398

+12.2609449,0.5079516172409058,0.539862871170044,0.6760380268096924,-0.0013268132426817382,-0.003587668481101684,-0.000877188043555793

+12.2697291,0.5079314112663269,0.5407616496086121,0.6773703694343567,-0.0003749615646274789,-0.0039013418116506282,-0.0011571218205578978

+12.279494,0.5074737668037415,0.5401550531387329,0.6758871078491211,-0.001472537305335558,-0.004149664421996283,-0.0007586863668787111

+12.2902252,0.5074425935745239,0.5410205721855164,0.6771581172943115,-0.0006992406634835418,-0.0039307585007074064,-0.001268049166728221

+12.2990103,0.5070226788520813,0.5404088497161865,0.6755884885787964,-0.0019064372678546137,-0.003968007439893258,-0.0008791655777033913

+12.3099132,0.5070011019706726,0.5412640571594238,0.676811158657074,-0.0010948617561977701,-0.0033667359032254346,-0.0012408031621006538

+12.3196773,0.5065516829490662,0.5406610369682312,0.6752290725708008,-0.002447200770810154,-0.003115990710798525,-0.000886718091793566

+12.3294346,0.5061496496200562,0.5407360196113586,0.6750829219818115,-0.002852193564391696,-0.0026702483930450996,-0.0007636605933150842

+12.3382166,0.5059270858764648,0.5405622124671936,0.6740471124649048,-0.004338647867839989,-0.00225322513066022,-0.0005235165401753633

+12.3499613,0.5060260891914368,0.5414212942123413,0.675520658493042,-0.003603197768746103,-0.001813297265249957,-0.0011076432856316528

+12.3596885,0.5056656002998352,0.5410398840904236,0.6742510199546814,-0.004768575983348892,-0.0013731495823988767,-0.0008145966535856913

+12.3684734,0.5057336091995239,0.5419304370880127,0.675624430179596,-0.003848037522246342,-0.0009251097074183066,-0.0011633370874968819

+12.3782329,0.5052630305290222,0.5414084792137146,0.6741997003555298,-0.005033317519449716,-0.0010793231636603662,-0.0004946933398041324

+12.3899456,0.50532066822052,0.5422213077545166,0.6755436062812805,-0.004147547870823045,-0.0008977215908466787,-0.0002838790836612531

+12.3997095,0.5047896504402161,0.541659414768219,0.6741403341293335,-0.004972679800402454,-0.0012356232693279616,0.0007849924414701028

+12.4094661,0.5047812461853027,0.5425547361373901,0.6753798723220825,-0.00424518192501715,-0.0013571946404145907,0.001175823037012946

+12.4192259,0.5043090581893921,0.5419463515281677,0.6738864183425903,-0.005163972846085062,-0.0016298198626927061,0.00206347699115471

+12.4299614,0.5043147802352905,0.5429022312164307,0.6752140522003174,-0.004359524406919901,-0.0018444166466363287,0.001574910043832319

+12.4406968,0.5038671493530273,0.5422912240028381,0.6737158894538879,-0.004980220093151174,-0.0016274495835336595,0.0016463104652804576

+12.4494812,0.5038959980010986,0.5431505441665649,0.6750646829605103,-0.004130377590562015,-0.0013031577503578439,0.001085543073130125

+12.4602173,0.5034805536270142,0.5425241589546204,0.6735163331031799,-0.004891216426927831,-0.0010014924232394,0.0011926324361518437

+12.4690008,0.5034850239753723,0.5434654951095581,0.6747980117797852,-0.004152864935315713,-0.000482097018192059,0.0008135168876659558

+12.4797372,0.5031059980392456,0.5428152084350586,0.6731871366500854,-0.004792939180200159,-0.0005813747531550219,0.0012011603829868024

+12.489238,0.5030964612960815,0.5438472032546997,0.6744511723518372,-0.003816028031989263,-0.00023156994804866075,0.0009395805706363901

+12.4989953,0.5026329159736633,0.543196439743042,0.6729111075401306,-0.00447026424210974,-0.00041274177856896147,0.001638192033004495

+12.5097349,0.5026310086250305,0.5441018342971802,0.6741587519645691,-0.0037725762491959687,-0.0003956396203246131,0.0016435129127380821

+12.5194919,0.5021708011627197,0.5434821844100952,0.6726840138435364,-0.004507396439303614,-0.0008410344113037895,0.0021374130298464334

+12.5292501,0.5021643042564392,0.5444694757461548,0.6739313006401062,-0.0037597349188276514,-0.0007722296941582393,0.0019222370434797715

+12.541124,0.5017291307449341,0.5438478589057922,0.6724139451980591,-0.0044917243439562505,-0.0006838567549336571,0.0024670922339973364

+12.5499087,0.5017157196998596,0.5448241233825684,0.6735848188400269,-0.0038794492204284508,-0.0005655771087869406,0.002190200835240892

+12.5586911,0.5012316107749939,0.5441917777061462,0.6720553040504456,-0.004217499226106513,-0.0009095157606808136,0.002851508132589394

+12.5684513,0.5012540817260742,0.5451964735984802,0.6732994318008423,-0.0031405054758629094,-0.0006434880706710522,0.0024902170169120285

+12.5782111,0.5008803009986877,0.5445766448974609,0.6716858148574829,-0.003751358153259754,-0.0005942416139076993,0.0029860225119458877

+12.587727,0.5009273290634155,0.5454072952270508,0.6728687286376953,-0.0032953885922395376,-0.00014897293410542808,0.0028056879125183364

+12.599423,0.5004794001579285,0.544785737991333,0.671298086643219,-0.004034818406509125,6.042726647687415e-05,0.0034386559175686453

+12.6091795,0.5005387663841248,0.5456768274307251,0.6725093126296997,-0.003442770850118603,0.00041738991698023973,0.0029795642420529234

+12.6199143,0.5001589059829712,0.5450698733329773,0.6709408164024353,-0.003962102031430536,0.0002007488076592783,0.003260197798451774

+12.6286983,0.5002202391624451,0.5460561513900757,0.6721832752227783,-0.002532854120663963,0.00048154905173655976,0.0029862736472664846

+12.6384662,0.49972525238990784,0.5454128980636597,0.6706440448760986,-0.003107036384799059,0.00045627561779975945,0.0033233514132856227

+12.6501702,0.4998350441455841,0.5462600588798523,0.672008752822876,-0.0018465641055091396,0.0008758697154648426,0.003040105974565657

+12.6579781,0.49943676590919495,0.545639157295227,0.6705325841903687,-0.0025885790327049886,0.0006568082353703979,0.0036605074339046907

+12.6696903,0.49952903389930725,0.5465441346168518,0.6718905568122864,-0.001365012905171842,0.000465607581852329,0.0034956863823319404

+12.6799339,0.49910590052604675,0.5458998084068298,0.670417845249176,-0.002309188390769422,-0.000139799131909638,0.0040007282551005425

+12.6895903,0.49916377663612366,0.5468239188194275,0.671681821346283,-0.0016610319319952562,0.00020047122974530267,0.0035155252048820387

+12.698374,0.49878308176994324,0.5461797118186951,0.6701927781105042,-0.002503948019803158,0.0002297897808142231,0.003981317790089229

+12.7091135,0.4988501965999603,0.5470992922782898,0.6714625358581543,-0.0015602046115587775,0.0008582773161601247,0.0038162129874833987

+12.7188716,0.49845728278160095,0.5464704632759094,0.670051097869873,-0.0022465401320084797,0.000845374311959249,0.004691012871102289

+12.7296055,0.4985441565513611,0.5474940538406372,0.6714356541633606,-0.0009966078024120362,0.0010697300915865312,0.00469122994869592

+12.7393684,0.49816247820854187,0.5468138456344604,0.6699174046516418,-0.0017694065415168085,0.0009065218346370874,0.005687639734721469

+12.7501019,0.4982517659664154,0.5477601885795593,0.6712836027145386,-0.0008830382585961912,0.000869191093760176,0.00568291746835261

+12.7588876,0.4979344308376312,0.5470679402351379,0.669766902923584,-0.0019017352398938707,0.0006389470931460793,0.0062539122630432846

+12.7696223,0.49803465604782104,0.5480027198791504,0.671139657497406,-0.0009916758765675365,0.0006061301933659266,0.005868124236914504

+12.7793823,0.497637003660202,0.54730224609375,0.669687032699585,-0.001750914953937642,0.0004946878890373948,0.006386696532452145

+12.7891428,0.49774470925331116,0.5482528805732727,0.6710705161094666,-0.00046839830636298324,0.0005583331346740326,0.006039201389409651

+12.7989031,0.4976568818092346,0.5475098490715027,0.6695170998573303,-0.0009735885789624842,0.0003420673561754013,0.006707598380917091

+12.808662,0.49772533774375916,0.548456609249115,0.6707372069358826,0.0002111132471809912,0.0008608284828431403,0.0065889380407422315

+12.8193996,0.49734848737716675,0.5477628707885742,0.6692971587181091,-0.0004560336759276717,0.0009033782453358302,0.007222452599880982

+12.8281848,0.49746277928352356,0.5486230850219727,0.6705614328384399,0.0008358585390100572,0.0012452361161966413,0.007320534527593261

+12.8389189,0.4971526563167572,0.5479528307914734,0.6691176295280457,0.00012811539317652082,0.0012914072556253252,0.0083755313865335

+12.8496541,0.4972688853740692,0.5488177537918091,0.6703288555145264,0.0010363949352180711,0.001622393385989919,0.008591570568757275

+12.8594139,0.4968923032283783,0.5481569766998291,0.6689619421958923,0.00015279176042816937,0.0016194550295245836,0.009632613818352849

+12.868198,0.4970478415489197,0.548987090587616,0.670261800289154,0.0010816645417536569,0.0017686767533802007,0.009853317340342085

+12.8789351,0.4966566860675812,0.5483072996139526,0.6689161062240601,0.00019627708540750598,0.001482191585458692,0.010789248317561093

+12.8896712,0.49681633710861206,0.5490861535072327,0.6702068448066711,0.0010055630925988183,0.0016832160513247623,0.010932890952105534

+12.8984543,0.49642595648765564,0.5483734607696533,0.6688634753227234,0.0007295394136176572,0.0009035286758254698,0.011706590589794005

+12.9101659,0.4965728223323822,0.5492686629295349,0.6701828241348267,0.0018186483200388485,0.0004137265187042183,0.01157809709270045

+12.9179742,0.4961773753166199,0.5485286116600037,0.6688737869262695,0.0013500719189284947,-0.0001858028799088339,0.012199304625564665

+12.9296866,0.4963124394416809,0.5494102835655212,0.6702276468276978,0.002074210527609507,-0.00034993988695387803,0.012075822208490001

+12.9394476,0.49593186378479004,0.5486263036727905,0.6689060926437378,0.0012859821915639572,-0.0007441650326313698,0.01264665231915322

+12.9501825,0.49605709314346313,0.5494274497032166,0.670249879360199,0.001971733527874458,-0.0004858314880718101,0.012400418536987253

+12.9599423,0.4957827925682068,0.548638105392456,0.6689069271087646,0.0014284085553152319,-0.000719102589810947,0.013178437000382247

+12.9697024,0.4959523379802704,0.5493552684783936,0.6703234910964966,0.0027565128924577883,-0.0006825978276772697,0.013355118114619046

+12.9794626,0.49568334221839905,0.548547089099884,0.6689803004264832,0.0022123553700830975,-0.0008798643558700972,0.014695781293643066

+12.9879616,0.4958450198173523,0.5492556095123291,0.6703382134437561,0.0032933880730019907,-0.00048546074142245344,0.015335080472661659

+12.9986432,0.4956401586532593,0.5484290719032288,0.6689420342445374,0.002499084396168836,-0.00039011741329571443,0.01680237037162369

+13.0093775,0.4958057105541229,0.5491299629211426,0.6702519059181213,0.0031201583290161278,3.607581713532414e-05,0.01718863109721805

+13.0181625,0.4955918490886688,0.5482996106147766,0.6688758134841919,0.0026043623955123753,0.0002572026475425022,0.018336265149216865

+13.028898,0.4957556128501892,0.5490052103996277,0.6701267957687378,0.0034099676493216254,0.000636411777226084,0.01834715816708908

+13.0396336,0.49548542499542236,0.5481600761413574,0.6688233017921448,0.0032704935304114064,0.0007478577898366901,0.01903609909066553

+13.0484182,0.4956933259963989,0.5487685799598694,0.6701569557189941,0.004191894866804889,0.001158567823154141,0.018837078326323167

+13.059154,0.49543529748916626,0.5478619933128357,0.6688329577445984,0.003577186025784307,0.0009603705484650206,0.01996426252602695

+13.0689146,0.4956459403038025,0.548530638217926,0.6701810359954834,0.0047434959756469134,0.0009728596084176381,0.02038601158793939

+13.0796508,0.49532052874565125,0.5475990176200867,0.6688995957374573,0.003782738273347541,0.0007115908189773022,0.021733982809890542

+13.0900746,0.4955112338066101,0.5480762720108032,0.6701648235321045,0.004288935872645403,0.000753259622302599,0.022335515773485935

+13.0988582,0.49524274468421936,0.5471411943435669,0.668976366519928,0.003523016152394628,0.0003678647821195166,0.023599240705559067

+13.1086286,0.4950777590274811,0.5467936396598816,0.6690375208854675,0.0034588760075268754,9.348870860793501e-05,0.02453764079911666

+13.119369,0.49523329734802246,0.5475708842277527,0.6703683733940125,0.00418694055063284,0.0005466763188884931,0.024468170415855126

+13.1291136,0.4950922131538391,0.5472473502159119,0.6705634593963623,0.0042134696578556485,0.0006763844471733874,0.02523710568206786

+13.1388754,0.4951457381248474,0.5475185513496399,0.6715121865272522,0.005058903261495301,0.0008401209669974509,0.025325269962237218

+13.1486445,0.49502530694007874,0.5471786260604858,0.6717753410339355,0.005068698581077703,0.0004363848568079659,0.025878682761711784

+13.1603467,0.49499887228012085,0.5471941828727722,0.6723955869674683,0.006268548057658285,8.743282924657749e-05,0.02639074595464817

+13.1691295,0.49489012360572815,0.5468220114707947,0.6726815700531006,0.006348323349051812,-0.0001983676746705952,0.02762119976061776

+13.1779379,0.49481073021888733,0.5466640591621399,0.673046350479126,0.007689495581331066,-0.0006703493916575746,0.029200215789584844

+13.1896594,0.494705468416214,0.5462490320205688,0.673336923122406,0.007812228232508856,-0.0009085843350224767,0.031243642965210584

+13.1993947,0.4945743978023529,0.5459154844284058,0.6734614968299866,0.00897100589686998,-0.0012801865775352265,0.033197252118320315

+13.2091529,0.4944651424884796,0.545445442199707,0.6737186908721924,0.008981849702060786,-0.0014749194431771231,0.03530510112827126

+13.218913,0.4943195581436157,0.5451406240463257,0.6736869215965271,0.010442159949356782,-0.0018084706498433473,0.03730926042452145

+13.2286879,0.49420416355133057,0.5446149110794067,0.673859179019928,0.01032950435950279,-0.001753491702856035,0.03898321079346122

+13.2394092,0.4940487742424011,0.5441582202911377,0.6737591028213501,0.011406687692896596,-0.0016785051299233146,0.040250288294092315

+13.2491703,0.4939267933368683,0.5435669422149658,0.6738485097885132,0.011322378834106642,-0.001421509898402409,0.04139166116360117

+13.2589298,0.4937744140625,0.5430910587310791,0.673620343208313,0.01218833998105865,-0.0014034384002935354,0.04218018107551243

+13.2686914,0.4936470687389374,0.5424335598945618,0.6736493110656738,0.012164751303933567,-0.001364395643039084,0.04303737880023468

+13.2794265,0.4934975504875183,0.5418685078620911,0.6734232902526855,0.013233162600770992,-0.0014087936152912784,0.043884015918610984

+13.2892392,0.4933661222457886,0.5411410927772522,0.6734083890914917,0.013303446910774184,-0.0014844560904225387,0.04500271661852003

+13.2979696,0.4932487905025482,0.5405440926551819,0.6731453537940979,0.01448605684364729,-0.0015154318636367802,0.0462260737583951

+13.3087062,0.4931158125400543,0.5397512316703796,0.6730899214744568,0.01444834899685335,-0.001487219936782218,0.04784849727227841

+13.3184649,0.49298202991485596,0.5389125943183899,0.6730256080627441,0.014417991858007994,-0.0013184374535114842,0.049452974880187975

+13.3292263,0.49284759163856506,0.5380268692970276,0.6729479432106018,0.01426723452818907,-0.0013365243956628067,0.051053605536017725

+13.3389639,0.4927125573158264,0.5370926260948181,0.6728541254997253,0.014128918063644719,-0.0013243734672829962,0.05265019366225618

+13.3487212,0.49257692694664,0.5361084342002869,0.6727414727210999,0.01398104903189018,-0.0012655684130243945,0.05418003675675942

+13.3594836,0.492440789937973,0.5350732207298279,0.6726028919219971,0.013756422457224542,-0.0012660313296049084,0.055629053681544645

+13.3692179,0.49230414628982544,0.5339854955673218,0.6724386811256409,0.013516719167155265,-0.0012685985591020853,0.05680940457812986

+13.3799527,0.49216699600219727,0.5328431129455566,0.6722652316093445,0.013382338527043541,-0.001235185850481277,0.058035197430249756

+13.3897139,0.4920293688774109,0.5316439867019653,0.6720969080924988,0.013323462986321779,-0.0011386435403504998,0.059293579699745524

+13.3985116,0.49189135432243347,0.5303871035575867,0.6719311475753784,0.013335168660709456,-0.0011917663678221307,0.06058617212267594

+13.4102097,0.4917529821395874,0.5290713906288147,0.6717638969421387,0.013381970742519698,-0.0008898296406955426,0.06190696314412317

+13.4189929,0.4916144013404846,0.5276954770088196,0.6715970635414124,0.013495660765691128,-0.0007486731409389615,0.063123044375495

+13.4287539,0.4914758503437042,0.5262577533721924,0.6714368462562561,0.013612078335304478,-0.0006031980267389908,0.06431145310734925

+13.4394903,0.49133747816085815,0.524756669998169,0.6712883114814758,0.013643279043362487,-0.0007358784667589192,0.06555119254101677

+13.4502253,0.4911993443965912,0.5231907963752747,0.6711550354957581,0.013597005057527724,-0.0008856015255973941,0.0669481017797658

+13.4590105,0.4910613000392914,0.5215584635734558,0.6710415482521057,0.013517637736400934,-0.0010280820525804218,0.0681524705010968

+13.4687701,0.4909231960773468,0.519858181476593,0.6709511876106262,0.013433475144460916,-0.0012365947107010507,0.06915370993131051

+13.4785289,0.49648037552833557,0.5155123472213745,0.666373074054718,0.010839891702337776,0.0009558341936050229,0.07136645620936798

+13.4892666,0.4965202212333679,0.5135689377784729,0.6661563515663147,0.01071360201435883,0.0011109662135591267,0.07196601379406792

+13.4990279,0.4968359172344208,0.5115088224411011,0.6657804846763611,0.00950870438467287,0.0016837336608845487,0.07245197901515939

+13.5097614,0.4968922436237335,0.5094175934791565,0.6656362414360046,0.00955777636733855,0.0018506892459724063,0.0726248118664655

+13.5195432,0.49706143140792847,0.5074583292007446,0.6655616760253906,0.008085884025158807,0.002208267542988894,0.0723759631549956

+13.5283305,0.4971345067024231,0.5052326917648315,0.6654804944992065,0.0083254774155867,0.0017739210448173045,0.07227832070158281

+13.5400176,0.49725520610809326,0.5033004283905029,0.6654938459396362,0.007095874328732473,0.0014275301915070554,0.07155998487790786

+13.5488009,0.49734774231910706,0.5009525418281555,0.6654497385025024,0.007347073890634918,0.0007724546423849768,0.07121000082181342

+13.5595372,0.49744313955307007,0.4990787208080292,0.6654958724975586,0.006462931512793129,0.00020599235388203013,0.0706021993347415

+13.5683214,0.4975581765174866,0.49662062525749207,0.6654943823814392,0.006781313945309795,-0.0009034107701102797,0.07055236242154646

+13.5780811,0.4976496696472168,0.49469247460365295,0.6656225919723511,0.0060959833005274945,-0.0015314523089248505,0.07024123533864564

+13.5897946,0.4978000521659851,0.491794615983963,0.6659369468688965,0.0056943780178892265,-0.0028032456420661335,0.07088032056685525

+13.5976059,0.49791857600212097,0.48914188146591187,0.6660487651824951,0.006158180556518842,-0.0036487479109911596,0.07144260328761688

+13.6073716,0.4980356693267822,0.48641711473464966,0.666372537612915,0.005693619177257449,-0.0042505111625502036,0.07193345741867872

+13.6200493,0.49814605712890625,0.48362335562705994,0.666540801525116,0.006105515989314112,-0.004931689077094128,0.07237543846771768

+13.6278571,0.49824610352516174,0.4810793697834015,0.6668875813484192,0.0057749044082132574,-0.005125458679128022,0.07224925852215759

+13.6395694,0.49835848808288574,0.47816234827041626,0.6670985221862793,0.006117071726161987,-0.00556860866692996,0.0722959779997532

+13.6483534,0.4984753727912903,0.4755657911300659,0.6674825549125671,0.0057246853709102385,-0.0056658783119316715,0.07170686536073446

+13.6581131,0.4985921382904053,0.472530335187912,0.6677301526069641,0.005955995127210636,-0.0059419759015325625,0.07140724272108961

+13.6678731,0.49870532751083374,0.46998879313468933,0.6681433320045471,0.005376474079556174,-0.00564444704378972,0.0702841064251433

+13.6776506,0.4988309144973755,0.46684637665748596,0.6684249639511108,0.005544071734490165,-0.005753631392570104,0.06976902764542933

+13.689346,0.498971164226532,0.4641919434070587,0.6689522862434387,0.004715549006639604,-0.005472602372465694,0.06863721807659807

+13.6991062,0.49910593032836914,0.4609453082084656,0.6692911982536316,0.004890859319330836,-0.005828922164631972,0.06827682295892729

+13.7089965,0.4992908239364624,0.4581277370452881,0.6698442697525024,0.00429026143248958,-0.005813181715390446,0.06742876542445642

+13.7177848,0.4994353950023651,0.45477789640426636,0.6702225208282471,0.004404885402962225,-0.00633384915894373,0.06714993392672645

+13.7285162,0.49965471029281616,0.4517672061920166,0.6707932353019714,0.003949411187363811,-0.006606096861234882,0.06680576917060467

+13.7392545,0.4944370687007904,0.4569443166255951,0.6682343482971191,0.006024493788063404,-0.009021520448299588,0.06405706020489423

+13.7492274,0.49472078680992126,0.45365068316459656,0.6685195565223694,0.005436851215926484,-0.009765440442470383,0.06430334872284647

+13.7589642,0.4947221875190735,0.4503367245197296,0.6689545512199402,0.005570530079078255,-0.010597206268245807,0.06477672538792144

+13.768719,0.4949590861797333,0.446931928396225,0.6692608594894409,0.00459058749897465,-0.011116628147907204,0.06538322329379126

+13.7784784,0.4949483871459961,0.44349053502082825,0.669714629650116,0.004663037052573167,-0.011465331262566564,0.06625863073832952

+13.7892157,0.4950937032699585,0.43996649980545044,0.6700471639633179,0.0040909123583251685,-0.011299633478768068,0.06731067626625294

+13.7979973,0.4950680136680603,0.43639621138572693,0.6704931259155273,0.004263936947377051,-0.011057713174110426,0.06850501834868572

+13.8087349,0.49527716636657715,0.4327527582645416,0.6707280874252319,0.0036331869992507204,-0.010175294800685847,0.06947341383574354

+13.8184964,0.49524450302124023,0.4290543794631958,0.6711285710334778,0.0039142542808840615,-0.009569081941481416,0.07014096793964476

+13.8282528,0.4953930974006653,0.42529603838920593,0.6713274121284485,0.003766655089451467,-0.008739565056553973,0.07037911336460753

+13.8389901,0.4953573942184448,0.4214676320552826,0.6716750264167786,0.004100396556808149,-0.008210390877840201,0.07033453996323469

+13.847778,0.49555477499961853,0.41764649748802185,0.6718613505363464,0.0039686417442089976,-0.0073320657427568,0.06978689643171286

+13.8585111,0.49448129534721375,0.4160248637199402,0.6717784404754639,0.006467888360641987,-0.00763858977749337,0.06743396620278286

+13.8682693,0.4946698248386383,0.41200897097587585,0.6715711951255798,0.006616507889904042,-0.007526219330658423,0.06721396231105839

+13.8790052,0.49459582567214966,0.4080505073070526,0.6717947125434875,0.006707002897866159,-0.007830288389017354,0.06711959252578828

+13.888766,0.49451491236686707,0.4040276110172272,0.6719943284988403,0.0066334294995355385,-0.008073654153954292,0.06722790812317653

+13.8985286,0.4944268465042114,0.3999406099319458,0.672165036201477,0.006499678452154906,-0.00831420669442605,0.06752983991888933

+13.9092621,0.49468526244163513,0.39573121070861816,0.6718839406967163,0.006058276926890277,-0.008195152585549027,0.06772501444495815

+13.9190217,0.4941437244415283,0.3929715156555176,0.671862781047821,0.008493010629619888,-0.00843848640541255,0.06661593525213357

+13.9287841,0.4941595494747162,0.38859793543815613,0.6714487075805664,0.00790071065729346,-0.0079004223209326,0.06643349844212354

+13.9385461,0.49403148889541626,0.3851166367530823,0.6716675758361816,0.009531255603147173,-0.007720278881393323,0.06558922830446046

+13.94735,0.49391618371009827,0.3805263638496399,0.6711211800575256,0.008825492406790536,-0.006866823022783589,0.06489031251362908

+13.9590419,0.4937916696071625,0.37690266966819763,0.6712929010391235,0.010923710393135557,-0.0065296990464841975,0.06331584877189426

+13.9687989,0.49363985657691956,0.37219521403312683,0.6707548499107361,0.010323406390559042,-0.005738573622283736,0.06196388225249435

+13.9776057,0.4934539198875427,0.3681126534938812,0.6708584427833557,0.011655676623274467,-0.005199007575251465,0.06007607333344711

+13.9883484,0.49180537462234497,0.36192381381988525,0.6696582436561584,0.01027288311851454,-0.005170769932151466,0.058639714850973364

+13.9990548,0.49160903692245483,0.3592306971549988,0.6700201034545898,0.011999384640777865,-0.004752502285989343,0.056841153539892164

+14.0088159,0.4907365143299103,0.3537420332431793,0.66881263256073,0.009875822282954201,-0.004874798887594505,0.056440646456151614

+14.0185746,0.4906516969203949,0.3506365418434143,0.6694332361221313,0.01054760507860564,-0.004561389806428012,0.0553934961539308

+14.0283401,0.4900140166282654,0.3450716435909271,0.6680747866630554,0.008776890878520507,-0.0043757267446711545,0.05519904613186026

+14.0390701,0.48998093605041504,0.3417072594165802,0.6687832474708557,0.009856046268082957,-0.003974840944351867,0.05403044326559726

+14.0478775,0.48947107791900635,0.3361365795135498,0.6674836874008179,0.008241099620417892,-0.0036225737221357393,0.05379851851024013

+14.0585911,0.48945844173431396,0.33258360624313354,0.668213427066803,0.010046284679361174,-0.002968678848497186,0.052434361509085245

+14.0683531,0.48902034759521484,0.32692185044288635,0.6668373346328735,0.008247202405311634,-0.0024129303532216114,0.05163766951684984

+14.0781422,0.4890032410621643,0.32327643036842346,0.6675169467926025,0.009949589510154743,-0.0018433325724880464,0.04973100336888448

+14.0888619,0.48855915665626526,0.3175158202648163,0.6660823225975037,0.00833847982087778,-0.0015111441099851478,0.04873388061494562

+14.0986068,0.48856788873672485,0.31363174319267273,0.6667368412017822,0.00943069238682474,-0.0012349585590421459,0.0469545752497422

+14.1091105,0.4881685972213745,0.30785053968429565,0.6653645038604736,0.007891358186878408,-0.0015019075121784004,0.04581373940753043

+14.1193053,0.48817241191864014,0.30389344692230225,0.6659387350082397,0.010640667392067985,-0.0014902379845827898,0.043794594834666606

+14.1286951,0.4877592921257019,0.29807546734809875,0.6646188497543335,0.008669083596571923,-0.0016699493487991866,0.042485271136491205

+14.1394334,0.4878126382827759,0.2939685583114624,0.6653086543083191,0.009647767330915132,-0.00139538267038877,0.04033743553011736

+14.1491861,0.4875110983848572,0.2881472706794739,0.6640663146972656,0.007412235031673306,-0.0016720273525149111,0.03880614322081503

+14.1579719,0.48757848143577576,0.28381016850471497,0.6647947430610657,0.007928987418923443,-0.0015531405191902654,0.036618483460373455

+14.1687093,0.48727551102638245,0.27794015407562256,0.6636704802513123,0.006290831938925304,-0.0016152798503583244,0.03533398736961607

+14.1784664,0.48707839846611023,0.2727067470550537,0.6636706590652466,0.005289312319701113,-0.0014105559253359047,0.03370879665174309

+14.1882316,0.48705142736434937,0.26722297072410583,0.6629593968391418,0.0030996778082799056,-0.0008568582906648674,0.03226899488091753

+14.1989654,0.4869271516799927,0.26316386461257935,0.6634809374809265,0.004346949988984647,-9.417395718447648e-05,0.029439984813246257

+14.2087379,0.48687490820884705,0.2577167749404907,0.6628672480583191,-0.000537556712326481,0.0008678016221352841,0.02804774285824885

+14.218484,0.48687124252319336,0.2532121539115906,0.6634103059768677,-0.0004837942733517715,0.0013451678470612106,0.025862430847976115

+14.2272679,0.4866357445716858,0.247473806142807,0.6626426577568054,-0.003601119227917736,0.0017143256506294848,0.02431192344501562

+14.2389814,0.4865190386772156,0.24308578670024872,0.6630247235298157,-0.0025562112514366715,0.0019102383010474078,0.02172851270079081

+14.248755,0.4862877130508423,0.2370879352092743,0.6619804501533508,-0.004200897718434698,0.0021936953276132268,0.020157108682600195

+14.258193,0.4862053692340851,0.2326403707265854,0.6623846888542175,-0.003779193337364034,0.002528258761235184,0.017394261877076107

+14.2685607,0.4860825538635254,0.2266937494277954,0.6613720059394836,-0.005145560586832746,0.00283631519673541,0.015020440437091404

+14.2783199,0.48605942726135254,0.22217828035354614,0.6618602275848389,-0.00488830196463763,0.0034620577590190405,0.011739340437996128

+14.2880818,0.4859396815299988,0.21628184616565704,0.6609904170036316,-0.005828441593225725,0.004036120062826996,0.009050858440220485

+14.2988174,0.485896497964859,0.21183337271213531,0.6613908410072327,-0.004522861389237914,0.004749313152057477,0.00558389457513734

+14.3085902,0.48578593134880066,0.20652657747268677,0.6615164875984192,-0.004825700391744014,0.005345962217587987,0.00273142144078463

+14.3183371,0.48572370409965515,0.20177917182445526,0.6617028117179871,-0.004188612974711206,0.005901346381761521,-0.00013590982296008086

+14.3280953,0.4859062731266022,0.19600450992584229,0.6610625386238098,-0.0033360156580289073,0.006299964984059954,-0.0020877395270209576

+14.339811,0.4858146011829376,0.1912107616662979,0.6612266898155212,-0.0026491013035494612,0.006331170203558435,-0.004303494200345249

+14.3485921,0.4859919846057892,0.18567004799842834,0.6609134078025818,-0.0001046132208731783,0.00630491781730974,-0.005768811838782635

+14.3583686,0.4858537018299103,0.18083608150482178,0.6609441041946411,-0.00031173679028060394,0.005977100032540368,-0.007454973201519766

+14.3691126,0.48592931032180786,0.17525045573711395,0.6606220602989197,0.0018624783327199498,0.0055185590309505435,-0.008731354631415578

+14.3780054,0.4857772886753082,0.17045250535011292,0.6606013774871826,0.002054328319468789,0.005032644989881324,-0.010674883063198711

+14.3886111,0.4857788681983948,0.1648378223180771,0.6602369546890259,0.0024759300388686803,0.004746931840449669,-0.012414354922176048

+14.3973916,0.4856680929660797,0.16015736758708954,0.6603119373321533,0.0023029498113240968,0.004312295108093667,-0.0150957593168574

+14.4082232,0.4856685400009155,0.1546940952539444,0.6601195335388184,0.0015968404782662363,0.004210331309629019,-0.01767558397172752

+14.4179822,0.48556649684906006,0.14994129538536072,0.6602123975753784,0.0007730271633268651,0.0040318504502478555,-0.020602297162373565

+14.4277429,0.4856589734554291,0.14473573863506317,0.6602931022644043,0.0011030149407306167,0.003768535496727438,-0.02321904974267035

+14.4384808,0.4855220913887024,0.14004957675933838,0.6603279113769531,0.000308127950054111,0.003542797864025406,-0.025938009718765184

+14.4521758,0.4854682981967926,0.1346043050289154,0.6600490212440491,-0.0014671983720400267,0.003168836916224674,-0.02821576480208315

+14.4599554,0.48585811257362366,0.12616980075836182,0.6607005000114441,-0.002125159046167879,0.0030305487336221644,-0.02997568872013222

+14.4697104,0.48706352710723877,0.12225348502397537,0.661517858505249,-0.0042295764155215534,0.003614439484032613,-0.03272387680427633

+14.478495,0.4870213270187378,0.11612264811992645,0.6613317131996155,-0.004548500489282652,0.0034056558767190477,-0.03392686163212609

+14.4892305,0.48780566453933716,0.11164094507694244,0.6617177128791809,-0.0061071594722133015,0.0032876643142320944,-0.03609747176619462

+14.4980142,0.4876265227794647,0.10595893859863281,0.661270022392273,-0.00625810667324239,0.0022381918069444553,-0.03738717009760474

+14.5087525,0.48827722668647766,0.10177670419216156,0.6620885133743286,-0.00836313574916238,0.001689858435123665,-0.03994007810087176

+14.5185113,0.48804613947868347,0.09629862755537033,0.661552369594574,-0.008612996689947314,0.0004052195422147648,-0.041847251361266206

+14.5283091,0.48861151933670044,0.0922776535153389,0.662559449672699,-0.010089296318300597,-0.0005824415531172865,-0.0447495921544656

+14.5390258,0.48824483156204224,0.08694669604301453,0.6617394089698792,-0.010114549739682586,-0.0021373620439077666,-0.04688508074622314

+14.5478174,0.4883589744567871,0.0821855217218399,0.661982536315918,-0.010333556274445828,-0.003174945827109512,-0.049446092039246534

+14.5575549,0.48809507489204407,0.07733648270368576,0.6612155437469482,-0.010180111258041975,-0.004464511268568389,-0.05181913479614288

+14.5683131,0.48872068524360657,0.07388269156217575,0.6624102592468262,-0.011637727730582562,-0.004258970429690176,-0.055218433067147236

+14.5800251,0.4887557029724121,0.06984275579452515,0.6625182628631592,-0.012157674617572493,-0.004748280198956611,-0.05728563180402206

+14.5888179,0.48887279629707336,0.06537042558193207,0.6627900004386902,-0.012847374278447142,-0.004572039346589149,-0.060222573053132354

+14.6004943,0.48875176906585693,0.061373114585876465,0.6627282500267029,-0.013007994825474213,-0.005317804237159188,-0.06215445873790916

+14.6083072,0.48884883522987366,0.0570426769554615,0.6630154848098755,-0.014840650314418335,-0.005028837622318269,-0.06454695111024158

+14.6200152,0.48863109946250916,0.05327041447162628,0.6629048585891724,-0.01523704408915033,-0.0055806733686837385,-0.06604745012697381

+14.6278228,0.4887050688266754,0.049088168889284134,0.6631413698196411,-0.015381646747673037,-0.005711973621934675,-0.06838737951615378

+14.6395347,0.48842570185661316,0.04542858898639679,0.6628768444061279,-0.015321582514845089,-0.0063087641651626385,-0.06937880933650384

+14.6483201,0.48847413063049316,0.04140452295541763,0.6630968451499939,-0.016825095778780084,-0.006312698479200102,-0.07116828363940035

+14.6590573,0.4881424605846405,0.03763681650161743,0.6627049446105957,-0.01677342034449168,-0.006867907971183978,-0.07176865793266006

+14.6668627,0.48816537857055664,0.033764295279979706,0.6629223227500916,-0.016278970438000664,-0.0066045237577140375,-0.07316950334432276

+14.6785753,0.48747625946998596,0.029254518449306488,0.661663293838501,-0.016260325901467063,-0.007135732915942844,-0.07327654991905659

+14.6873737,0.48779481649398804,0.0265146866440773,0.6627128720283508,-0.017199205528357703,-0.006950200383815886,-0.07458218928043783

+14.6980985,0.4870707094669342,0.022091228514909744,0.6614102125167847,-0.01707931342943077,-0.007679944895744908,-0.07474511764868806

+14.7068784,0.48742926120758057,0.019573381170630455,0.6623963713645935,-0.018247690654113514,-0.007633213755771417,-0.07607403266501483

+14.7195666,0.487118661403656,0.016404595226049423,0.6620545983314514,-0.018102165115212586,-0.008131438182661991,-0.07623223785455398

+14.7273747,0.4870637357234955,0.01301535777747631,0.6621971726417542,-0.019296815972894916,-0.007637264171396743,-0.07763249930656035

+14.7390872,0.4863050878047943,0.008774129673838615,0.660880982875824,-0.019089801502636186,-0.007969507850474329,-0.07739283053451063

+14.746895,0.4865938425064087,0.00677601620554924,0.6620301604270935,-0.020247357992183444,-0.0074440190316650955,-0.07833135316295062

+14.759584,0.48610395193099976,0.003785944078117609,0.6614874601364136,-0.019729708686595723,-0.007561456159872796,-0.0777009845450296

+14.7683663,0.48599299788475037,0.0007253608200699091,0.6615577340126038,-0.02124630588692293,-0.006858391845462722,-0.0781443466785678

+14.7791035,0.4856027662754059,-0.0019437281880527735,0.6611371636390686,-0.02080238731631632,-0.007041029100140774,-0.0770546427490462

+14.7878866,0.48547208309173584,-0.0048293741419911385,0.661249041557312,-0.02112662407458473,-0.006522630715573855,-0.07727143236216392

+14.7995982,0.48496729135513306,-0.00758209777995944,0.660741925239563,-0.020579520343539298,-0.006688040412247594,-0.07601459859639993

+14.8083831,0.4848101735115051,-0.010307732969522476,0.6608763933181763,-0.021802148669088972,-0.006276983579170541,-0.07611658686163952

+14.8200956,0.4843258857727051,-0.013035529293119907,0.6602194309234619,-0.02137755655972458,-0.006688363008876,-0.07527533865394011

+14.8279061,0.4841451942920685,-0.015613887459039688,0.6603075265884399,-0.022336420370429648,-0.005907232931573118,-0.07593063154262085

+14.8376688,0.4832622706890106,-0.01930348575115204,0.6589683890342712,-0.021690121129841644,-0.005768975778447227,-0.07544621800925232

+14.8474269,0.48303449153900146,-0.02178828790783882,0.6589890718460083,-0.021742883388468817,-0.004932979922251266,-0.07559814394083697

+14.8591343,0.4827742576599121,-0.02281283214688301,0.659276008605957,-0.021050445544962854,-0.004427846949421219,-0.07496720548684474

+14.8679231,0.4825567603111267,-0.025069426745176315,0.6593347191810608,-0.022803532845252945,-0.0024930885540310334,-0.07662962605167456

+14.879635,0.4820747673511505,-0.027252158150076866,0.6587621569633484,-0.02210690929994897,-0.0017448275069248769,-0.07544727418257659

+14.8874431,0.481841117143631,-0.02935529500246048,0.6588284373283386,-0.023750056429114104,-0.00021807501806922098,-0.07552062035228939

+14.8991617,0.4814130961894989,-0.03136226907372475,0.6583523154258728,-0.02308768685565039,0.00014388143020313494,-0.0737526670656619

+14.9089112,0.4811737537384033,-0.0333111435174942,0.658420741558075,-0.02484890216658547,0.0010752389811780315,-0.0734938422268451

+14.919651,0.48070797324180603,-0.035308513790369034,0.6579579710960388,-0.023859123779898586,0.0009917045904287883,-0.0713373107827673

+14.9284304,0.48046424984931946,-0.037113722413778305,0.6580245494842529,-0.025271602013985168,0.0019141329909812825,-0.0709014261066359

+14.9381907,0.47954484820365906,-0.04041256010532379,0.6567246317863464,-0.024322064580210308,0.0017822477534038485,-0.06890943105872702

+14.9479503,0.4792689085006714,-0.0421455092728138,0.6568037867546082,-0.024514667093620265,0.001648160153993442,-0.06815109379003902

+14.9596619,0.4790050685405731,-0.042634863406419754,0.6569749712944031,-0.02389619784922741,0.0013891053235739153,-0.0665303284708835

+14.9684474,0.4787527620792389,-0.04416382685303688,0.6571267247200012,-0.025340575389035832,0.002884360255662112,-0.06770081883264308

+14.9772301,0.47789666056632996,-0.04720684885978699,0.6559233069419861,-0.02425713953321095,0.003195606522376082,-0.06607327896000373

+14.9879846,0.4776109457015991,-0.04867677390575409,0.6560510396957397,-0.024322139042168567,0.004299878871950431,-0.06577439543656953

+14.9984394,0.4767557978630066,-0.051182132214307785,0.6549798250198364,-0.0238099646979256,0.004939750819720535,-0.06448841309868746

+15.0072272,0.47643572092056274,-0.05259322375059128,0.6550748944282532,-0.02401604438355464,0.006559364137569767,-0.063868865304973

+15.018939,0.47667285799980164,-0.05181528255343437,0.6560462713241577,-0.023416407937475393,0.007415404191829139,-0.06239249673452724

+15.02772,0.47643277049064636,-0.052960094064474106,0.6562574505805969,-0.0223833230795774,0.009933558270319495,-0.06380608792951217

+15.0394489,0.476309597492218,-0.05353948846459389,0.656531810760498,-0.02159573587528394,0.010080239729253652,-0.06153042577510517

+15.0482159,0.476096510887146,-0.054544929414987564,0.6567692160606384,-0.019547755393981767,0.011424264119352608,-0.06136224279912163

+15.0579751,0.4757708013057709,-0.05636369809508324,0.6562425494194031,-0.01899338594500578,0.010979980009843758,-0.058745280140212304

+15.0677394,0.47557616233825684,-0.057280126959085464,0.6565155982971191,-0.019724757090759222,0.011349603924232527,-0.05773976695035571

+15.0794473,0.4752994775772095,-0.058692000806331635,0.6562455892562866,-0.019561102478830222,0.011355268533420492,-0.05490287777096345

+15.0872602,0.4751274883747101,-0.05951038748025894,0.6565820574760437,-0.020052589270024793,0.011983551524374698,-0.05402123888547683

+15.0986553,0.47492486238479614,-0.06076696515083313,0.6564931273460388,-0.019770222995050605,0.011893270302841258,-0.05162044022246919

+15.1064676,0.474778413772583,-0.06149614602327347,0.6568238139152527,-0.020095528537702113,0.012791302087503759,-0.051192925176452644

+15.1201676,0.47455859184265137,-0.06232532486319542,0.6569886207580566,-0.019863103446230098,0.012845602520564662,-0.04900105282824018

+15.1270005,0.47443661093711853,-0.0629589855670929,0.6573381423950195,-0.017089664053680856,0.013660157386261277,-0.048872555037298586

+15.1397157,0.47417721152305603,-0.06418310105800629,0.6571342945098877,-0.017001747647067644,0.013368883391127654,-0.046715398845549136

+15.1475645,0.47407832741737366,-0.06474213302135468,0.6575154066085815,-0.017809294261118068,0.013747702020077291,-0.0465584485449242

+15.1583032,0.4733479917049408,-0.06744110584259033,0.656633198261261,-0.017647043629946745,0.01305046780861316,-0.044351076190126563

+15.1670873,0.4732445180416107,-0.0679941326379776,0.6570226550102234,-0.018525862404250193,0.012460775512905985,-0.04341568836008068

+15.1778247,0.4724319279193878,-0.07004999369382858,0.65604567527771,-0.018472241407027537,0.011156966000093598,-0.04089647274792326

+15.1875826,0.472304105758667,-0.07061159610748291,0.656355082988739,-0.01917807682875707,0.01084658773913639,-0.03979972740941974

+15.1983192,0.47167423367500305,-0.07210130244493484,0.655565619468689,-0.018814388335829758,0.010395585627087641,-0.03793979749764752

+15.208079,0.47152775526046753,-0.07265637069940567,0.6558271050453186,-0.019477708534523696,0.011014328202852931,-0.03727655200906391

+15.2178672,0.47105059027671814,-0.07375060021877289,0.6553670763969421,-0.01914322209785581,0.011356122998706525,-0.036256739200080226

+15.2285766,0.4709002673625946,-0.07427548617124557,0.6555936336517334,-0.019793510644790967,0.012146533677695788,-0.03609883628503116

+15.2402874,0.4722781181335449,-0.0723240077495575,0.6572456359863281,-0.020196049845288777,0.01254001478991939,-0.0355022418545754

+15.2480951,0.47229424118995667,-0.07253687083721161,0.657625138759613,-0.02158647422230803,0.015576127091022955,-0.03932620134294901

+15.257855,0.47205013036727905,-0.07431959360837936,0.6571230888366699,-0.02196040433967689,0.015514043292305395,-0.03846079817214622

+15.2676151,0.4720674157142639,-0.07453703135251999,0.6575197577476501,-0.02270409140247718,0.015692235285686126,-0.038388415496010624

+15.2803038,0.4727367162704468,-0.07306911796331406,0.6589066386222839,-0.022863012424658036,0.016495285541886076,-0.03956039524897841

+15.2881112,0.4728523790836334,-0.07308651506900787,0.6593831181526184,-0.023438238354783373,0.0159013034145702,-0.03873103593331175

+15.2998231,0.4729190766811371,-0.0737917572259903,0.6595038771629333,-0.020106378230143652,0.015052192379666578,-0.03689251891804188

+15.3066552,0.4730547368526459,-0.07379086315631866,0.6599733233451843,-0.02060592587756003,0.014484044939469767,-0.035445548079211686

+15.320319,0.47321274876594543,-0.0746716633439064,0.660001277923584,-0.01868906313105263,0.013505848462313775,-0.03327453111948547

+15.327151,0.473370760679245,-0.07464230060577393,0.6604792475700378,-0.019324769197939146,0.012634110881475985,-0.0314546770630471

+15.3378877,0.4730171859264374,-0.07672317326068878,0.6597739458084106,-0.01836218202853613,0.01133958272561441,-0.028269095142452363

+15.3476463,0.4731738269329071,-0.07670066505670547,0.6602340936660767,-0.019147756025980227,0.010740103923233596,-0.026197587843932554

+15.3564313,0.47273099422454834,-0.07847384363412857,0.6595520377159119,-0.019023731976482727,0.009651806460718726,-0.023270952661702156

+15.3671676,0.47287043929100037,-0.07848090678453445,0.6599229574203491,-0.01986113442659935,0.00878295530524896,-0.02210599497796764

+15.3788855,0.47254398465156555,-0.07971762120723724,0.6593087315559387,-0.019916534063530125,0.00757569062918344,-0.02056314308420279

+15.3886546,0.47266465425491333,-0.07975279539823532,0.6595456600189209,-0.02074252265780325,0.0071866378687020956,-0.020558213765250518

+15.397423,0.47242528200149536,-0.08059216290712357,0.659074604511261,-0.019345914638852976,0.0064402943497892445,-0.02028700802427364

+15.4077822,0.47253039479255676,-0.08064544945955276,0.6592501997947693,-0.02006109823208313,0.006382918140863973,-0.02096975917602

+15.4175462,0.47239577770233154,-0.08127196133136749,0.6590872406959534,-0.02095329928098795,0.0060967534214183515,-0.02106013580145316

+15.4274076,0.4724920392036438,-0.0813356265425682,0.6592284440994263,-0.021629224553756,0.00634293604590311,-0.021760338224752766

+15.4380381,0.4723869860172272,-0.08170866966247559,0.6590549349784851,-0.0205282858833299,0.006226261131274346,-0.021686174709482378

+15.4468218,0.4724788963794708,-0.08176454156637192,0.6591436266899109,-0.02117900208930783,0.006298101430420121,-0.02192829622435276

+15.4575582,0.4724152982234955,-0.0821135863661766,0.6592180132865906,-0.0213425998691452,0.005887843449637346,-0.02139375976656298

+15.4673355,0.47250673174858093,-0.08215932548046112,0.6593462228775024,-0.022024469316993603,0.00593540765265292,-0.020881842223286824

+15.4780576,0.4724775552749634,-0.08240675926208496,0.6595220565795898,-0.022413040884390226,0.005625109323459052,-0.02015368305891874

+15.4868421,0.47257134318351746,-0.08243536204099655,0.6596717238426208,-0.023002417301800294,0.005815666401406661,-0.019740924542228512

+15.4983205,0.47254881262779236,-0.08262041956186295,0.6598357558250427,-0.023141043636948275,0.0058900497204335545,-0.019239896785247214

+15.5070223,0.47264569997787476,-0.08262958377599716,0.6599809527397156,-0.023590734595554462,0.005953174744833423,-0.01913741648106177

+15.5198532,0.4760954976081848,-0.08093129098415375,0.6622354984283447,-0.021903584114906442,0.009323821326712148,-0.022806605997055248

+15.5276705,0.4764312505722046,-0.08066819608211517,0.6625746488571167,-0.022320914560782924,0.009354893731185065,-0.023149369727426646

+15.5375105,0.47662046551704407,-0.08173034340143204,0.6623309254646301,-0.021909874623031563,0.008836720019600043,-0.022400339191774626

+15.5472273,0.4769531190395355,-0.08148816972970963,0.6627325415611267,-0.022408653272571227,0.008402947264601529,-0.02247205823869552

+15.5599151,0.47807538509368896,-0.08031778037548065,0.6640557646751404,-0.02157361439045117,0.008369692510604893,-0.02297608136173294

+15.5687004,0.47839221358299255,-0.08206246048212051,0.663722038269043,-0.02193664987404033,0.007396877530978975,-0.022575265822557387

+15.5804168,0.479278564453125,-0.08015437424182892,0.6649805903434753,-0.021925848786796865,0.0065021800327294856,-0.021495395387696164

+15.5891965,0.4794054627418518,-0.08211785554885864,0.6646114587783813,-0.022188249488681498,0.0053093707793093955,-0.020374100166007467

+15.597984,0.47983410954475403,-0.08180621266365051,0.6651305556297302,-0.022523506196849064,0.0037299370190904896,-0.018237402569644106

+15.6103121,0.4797254800796509,-0.08318973332643509,0.6645710468292236,-0.022694296786383246,0.0025104212278323364,-0.016636761674614815

+15.6171742,0.4801252782344818,-0.08289593458175659,0.6650301814079285,-0.02212512586029432,0.0007429925419419133,-0.014177437700533568

+15.6288516,0.48008155822753906,-0.08387193083763123,0.6645586490631104,-0.022355198818891968,-0.0004355580157026472,-0.0129522080006471

+15.6386166,0.4804462790489197,-0.08360370993614197,0.6649966239929199,-0.022472775021639264,-0.0021518511270664474,-0.011235399546400954

+15.647396,0.48080965876579285,-0.08332380652427673,0.6654551029205322,-0.022747499205703726,-0.0030602730200879062,-0.010964883046891895

+15.6572663,0.48075535893440247,-0.08390269428491592,0.6650275588035583,-0.021925842905662407,-0.004253897432092764,-0.01055009376865277

+15.6698751,0.48077210783958435,-0.08425764739513397,0.6648385524749756,-0.022058781730034057,-0.00453323811484745,-0.01116449244382457

+15.6768116,0.48106276988983154,-0.08403951674699783,0.6651660799980164,-0.022079686310730616,-0.005333571989475837,-0.011210393249182903

+15.6874117,0.4813486933708191,-0.08381087332963943,0.6654761433601379,-0.022194976860416517,-0.005761911507264105,-0.012047740134159613

+15.6971714,0.481321781873703,-0.08403962105512619,0.6652762293815613,-0.021553309860734848,-0.006174463032506066,-0.012028465284622177

+15.7098596,0.4813258945941925,-0.08412784337997437,0.665145993232727,-0.021725983610107927,-0.006096104013918952,-0.012412651211151858

+15.7186435,0.48154744505882263,-0.08393962681293488,0.6653494238853455,-0.0208278385647284,-0.006465159088182085,-0.012105631119778896

+15.7294832,0.48157474398612976,-0.08398116379976273,0.6653271317481995,-0.020949581020199056,-0.0064214952295433905,-0.01202603985591992

+15.7363157,0.48176810145378113,-0.08379749953746796,0.6654643416404724,-0.021201589908332735,-0.006421169942303213,-0.011345882408369755

+15.7499801,0.48178964853286743,-0.08380316942930222,0.6654395461082458,-0.021288157420913358,-0.006232219747874767,-0.011229527935216548

+15.7577937,0.48195725679397583,-0.08362045139074326,0.6655365228652954,-0.02136929385280982,-0.0062928893344966945,-0.010704409194481587

+15.7695008,0.4819898307323456,-0.08355481177568436,0.6654808521270752,-0.02138547452584639,-0.005920150008531408,-0.01047439463065656

+15.7782824,0.4862901568412781,-0.08180616050958633,0.6674755811691284,-0.0210424919756299,-0.005927997657546295,-0.010104649085376595

+15.7890373,0.48638999462127686,-0.08272791653871536,0.66675865650177,-0.021315372375332767,-0.002004759037835754,-0.014034393138919713

+15.7997547,0.48753684759140015,-0.08037785440683365,0.66825932264328,-0.02064979149066633,-0.0014738830603899075,-0.014598238620119707

+15.8095166,0.4878385066986084,-0.08208058774471283,0.6675390601158142,-0.020891188980493594,-0.0014693311915914408,-0.015142660865323636

+15.8173234,0.4882490932941437,-0.08166691660881042,0.6677262783050537,-0.020191558044339156,-0.0021887364859642165,-0.01440183715377664

+15.8300126,0.4882422089576721,-0.08302926272153854,0.6668760180473328,-0.020370780127564013,-0.0027583151300258272,-0.014166042565538207

+15.8378347,0.4886510968208313,-0.08260359615087509,0.6670514345169067,-0.019694228729626666,-0.004321633176732702,-0.012480122206393027

+15.8485557,0.488648384809494,-0.08352764695882797,0.666317343711853,-0.019857658338500048,-0.005578560337697537,-0.011229257757915957

+15.859293,0.48978057503700256,-0.08054563403129578,0.6681139469146729,-0.02010539473918788,-0.0064322168088566814,-0.010559618686975844

+15.8690523,0.48990345001220703,-0.08224325627088547,0.667294979095459,-0.020364747077248148,-0.007840342338691585,-0.009410432276176151

+15.8797903,0.4907343089580536,-0.07990087568759918,0.6686582565307617,-0.0205458519293925,-0.008989469262363948,-0.008449018554968261

+15.8895494,0.4906690716743469,-0.0818498507142067,0.6677830815315247,-0.02079948016798959,-0.009930713467859098,-0.008037319392078735

+15.9002846,0.4915499985218048,-0.07976356148719788,0.6688917875289917,-0.022006365267843043,-0.010822570539354162,-0.007582040788903956

+15.9100437,0.49143779277801514,-0.08178097009658813,0.6679964661598206,-0.023012387015352777,-0.011649884006841716,-0.006621202738694338

+15.916875,0.49177733063697815,-0.081366628408432,0.6681430339813232,-0.023137926188705197,-0.011801441599881437,-0.006685781658581134

+15.9295679,0.49152374267578125,-0.0827430710196495,0.6671808362007141,-0.023157806483361784,-0.011767926040532386,-0.006577072477174517

+15.9363997,0.4918016493320465,-0.08238508552312851,0.667239785194397,-0.023925515069584662,-0.012324789437750942,-0.0051979008257075085

+15.950059,0.49163490533828735,-0.08321050554513931,0.6664196252822876,-0.024016934142433343,-0.012828474236941024,-0.003939325100754638

+15.9578717,0.49185189604759216,-0.08290276676416397,0.666454017162323,-0.024051756413770945,-0.012820878116771394,-0.0035460594129647777

+15.9695837,0.4917401671409607,-0.08332981169223785,0.6658695936203003,-0.024267639947255993,-0.013340701139232476,-0.002413158242119505

+15.9773917,0.4919022023677826,-0.08306370675563812,0.6659104824066162,-0.024410369832786112,-0.013536402493392326,-0.002468038073694744

+15.9901065,0.49181386828422546,-0.08321834355592728,0.6654650568962097,-0.0237990363669809,-0.014008504512147597,-0.0024199342751821777

+15.9988595,0.4933739900588989,-0.07990843802690506,0.6678140759468079,-0.02380164458883412,-0.014034924068321191,-0.0030372410637569433

+16.0095954,0.493358850479126,-0.08127453923225403,0.6669697165489197,-0.02468870857359662,-0.012236436122643541,-0.00614416258608293

+16.0183814,0.4940192699432373,-0.07880639284849167,0.6683953404426575,-0.02456014695898862,-0.011855992070312864,-0.0072362217549490505

+16.0281393,0.4938632547855377,-0.0805719718337059,0.6675920486450195,-0.02456203817942102,-0.010935232703337584,-0.00918645174981331

+16.0369277,0.49405401945114136,-0.08015235513448715,0.6677636504173279,-0.02471128621526604,-0.011396475575267346,-0.008398608965414398

+16.049611,0.49373385310173035,-0.08140485733747482,0.6669782400131226,-0.02463411608591202,-0.012245016077111977,-0.006924575888644036

+16.0593716,0.49469029903411865,-0.0786258801817894,0.6685160398483276,-0.026060707036547278,-0.011874186999931894,-0.007407467577070043

+16.0691359,0.4944719076156616,-0.08035694062709808,0.6677495837211609,-0.02624395066587991,-0.01283059015349057,-0.004913270187333668

+16.0759638,0.49461567401885986,-0.07995077967643738,0.6679956316947937,-0.02624395066587991,-0.01283059015349057,-0.004913270187333668

+16.0906033,0.4942353665828705,-0.08110950887203217,0.6671608686447144,-0.02587005593742926,-0.01422098180716766,-0.001402944816450628

+16.0974354,0.49431490898132324,-0.08077007532119751,0.667326033115387,-0.02587005593742926,-0.01422098180716766,-0.001402944816450628

+16.1101232,0.49397221207618713,-0.08144698292016983,0.6666193008422852,-0.025174042304273208,-0.01462851904535479,0.0005768797298178844

+16.1169597,0.4939889907836914,-0.08116787672042847,0.6667284369468689,-0.025174042304273208,-0.01462851904535479,0.0005768797298178844

+16.1286668,0.493691086769104,-0.08153508603572845,0.6662018895149231,-0.024612025206446994,-0.014365880589001056,0.00012577581584600708

+16.1394079,0.49499648809432983,-0.07842133939266205,0.6682661771774292,-0.025610095384630358,-0.01226623888662185,-0.0038963826595474907

+16.1501403,0.4948486089706421,-0.07986698299646378,0.6674765348434448,-0.025656960343013988,-0.012412660984899546,-0.0039799600944351735

+16.158923,0.49534425139427185,-0.07757123559713364,0.6688150763511658,-0.026429002931775154,-0.011247362161790748,-0.006196920163566345

+16.1686855,0.4949580729007721,-0.07921487838029861,0.6679840087890625,-0.025715998697059435,-0.01118552812294229,-0.006119813628433895

+16.1775197,0.49497848749160767,-0.0788365975022316,0.6681930422782898,-0.025390471529194915,-0.010905530342531337,-0.006571999193517982

+16.1901553,0.4944746196269989,-0.07995462417602539,0.6673921942710876,-0.024581497568815464,-0.01121610617344558,-0.0052528474825567694

+16.1979631,0.4944378733634949,-0.07963529229164124,0.6675488352775574,-0.024288561311411012,-0.01098332871187834,-0.004741621612871963

+16.2086986,0.49403616786003113,-0.08015318214893341,0.6669135093688965,-0.023407930778959394,-0.011197167384021886,-0.0030360854938776016

+16.2174878,0.49403616786003113,-0.08015318214893341,0.6669135093688965,-0.023407930778959394,-0.011197167384021886,-0.0030360854938776016

+16.2293064,0.4935738444328308,-0.08019619435071945,0.6664556860923767,-0.022126065283240005,-0.011388121984821397,-0.0006947705480341887

+16.2361431,0.4935738444328308,-0.08019619435071945,0.6664556860923767,-0.022126065283240005,-0.011388121984821397,-0.0006947705480341887

+16.249943,0.49309617280960083,-0.08008319139480591,0.6660844683647156,-0.02130035403770658,-0.010900136797433294,-0.00015963916422524166

+16.2587192,0.4945240318775177,-0.07660213112831116,0.6685393452644348,-0.02130035403770658,-0.010900136797433294,-0.00015963916422524166

+16.2694556,0.49422720074653625,-0.07793179899454117,0.667762815952301,-0.022715870248159988,-0.007745374236140536,-0.004427657228532113

+16.2782391,0.49467167258262634,-0.07543092966079712,0.6692638397216797,-0.022715870248159988,-0.007745374236140536,-0.004427657228532113

+16.2899521,0.4941924810409546,-0.07709146291017532,0.6684685945510864,-0.022687937750426938,-0.00568760247644761,-0.007173974620827911

+16.2977635,0.4941924810409546,-0.07709146291017532,0.6684685945510864,-0.022687937750426938,-0.00568760247644761,-0.007173974620827911

+16.3084941,0.49360719323158264,-0.07825647294521332,0.6676900386810303,-0.022255368322044222,-0.005485654228071035,-0.006685862063683924

+16.3173346,0.4934929609298706,-0.07790365070104599,0.6678940057754517,-0.021956575927082146,-0.005149105899312826,-0.006589198888673361

+16.3281971,0.49297311902046204,-0.07855957001447678,0.6672368049621582,-0.021738379295013724,-0.005525742792486849,-0.004769347240772442

+16.3368541,0.49281609058380127,-0.07825617492198944,0.6673939228057861,-0.021474912255818917,-0.005682230160999476,-0.0033321931460110624

+16.3495438,0.492360919713974,-0.07855255156755447,0.6668872833251953,-0.020259890628532524,-0.006355175566324959,-0.0012346019077272095

+16.3574859,0.4921676814556122,-0.07828959822654724,0.6669560670852661,-0.020179675337040005,-0.0066469968954895675,0.00010851814606590707

+16.3690623,0.491519570350647,-0.07818295806646347,0.6665583848953247,-0.018724286761510375,-0.006853418512367364,0.0018517274912469759

+16.3768746,0.491519570350647,-0.07818295806646347,0.6665583848953247,-0.018724286761510375,-0.006853418512367364,0.0018517274912469759

+16.3886007,0.4908812344074249,-0.07798349857330322,0.6663354635238647,-0.017247209381024118,-0.005337183041947754,0.0005827101880385375

+16.3993197,0.4908812344074249,-0.07798349857330322,0.6663354635238647,-0.017247209381024118,-0.005337183041947754,0.0005827101880385375

+16.4091147,0.4902498722076416,-0.07773726433515549,0.6661829352378845,-0.01659892664300457,-0.0029070173078624474,-0.0016843641383785096

+16.4198485,0.4926256537437439,-0.07464278489351273,0.668786883354187,-0.018249825533478287,0.0010972332489462063,-0.007052495000045868

+16.4285988,0.49237850308418274,-0.07605549693107605,0.6679015755653381,-0.01740699334700205,0.000688482325869861,-0.006073461492222723

+16.4373826,0.49226701259613037,-0.07564693689346313,0.6681211590766907,-0.017756106306628317,0.0017485005807051487,-0.007259070145453231

+16.4481223,0.4918702244758606,-0.07638176530599594,0.6675686240196228,-0.01622003158923606,0.002119186175542153,-0.007003914870069675

+16.4569365,0.49173328280448914,-0.07601746171712875,0.6678032279014587,-0.016541399429173157,0.002450738162983604,-0.006986502716224909

+16.4686146,0.49130088090896606,-0.07643768936395645,0.6672861576080322,-0.014911310719209763,0.001862571461458004,-0.005404141777307676

+16.4775294,0.49114057421684265,-0.07610835880041122,0.6674666404724121,-0.01534698479354683,0.0011080816078877303,-0.004273051594764245

+16.4881631,0.49073347449302673,-0.07628155499696732,0.66706383228302,-0.013971789054169192,0.0001933766893211186,-0.0023081508870555776

+16.4969192,0.4905524253845215,-0.07598256319761276,0.6671910881996155,-0.014508224588296493,-0.00024719235506287057,-0.0010652495812449921

+16.5076604,0.4901575744152069,-0.07604607194662094,0.6668970584869385,-0.01406805866130012,-0.0006650635193569197,0.0003782685576900162

+16.5174185,0.48995622992515564,-0.07577928900718689,0.6669867038726807,-0.014597973796564303,-0.0006141988710834713,0.0008447182481210892

+16.5281554,0.4895927906036377,-0.07578326761722565,0.6668277978897095,-0.015245992080705966,-0.0004956701590638782,0.0011602886948333486

+16.5388866,0.4919494688510895,-0.07313629984855652,0.6690527200698853,-0.018307099517928842,0.003646899868888262,-0.0031216204848731883

+16.5486742,0.49165230989456177,-0.07446937263011932,0.6680901646614075,-0.015867660639337335,0.0032007484908823654,-0.0022703757270914867

+16.5564805,0.4916021227836609,-0.07407844811677933,0.6683305501937866,-0.016337788471057355,0.004084342878514783,-0.0032433511362678896

+16.5681664,0.4912678301334381,-0.07485755532979965,0.6677708029747009,-0.015939651266600113,0.004454199605088954,-0.0033890249363900107

+16.5779312,0.49214938282966614,-0.07178781926631927,0.6697226762771606,-0.016489399380708442,0.004914373977373303,-0.004083211135461328

+16.5876869,0.4918946325778961,-0.07368987798690796,0.6687161326408386,-0.018932892777041833,0.005829446129629693,-0.0046848060770695605

+16.5964704,0.4918901026248932,-0.07329807430505753,0.6689440011978149,-0.019367472180552014,0.005294448488222397,-0.004262418007197334

+16.6082331,0.4914802610874176,-0.07431547343730927,0.66815185546875,-0.019776809040524788,0.0041826719997448665,-0.002622377104273245

+16.6159914,0.4914548099040985,-0.07396519929170609,0.6683108806610107,-0.02004216407217539,0.0035817433120025424,-0.0016469817872632568

+16.6286793,0.4910651743412018,-0.07454609125852585,0.6675661206245422,-0.01999650982055604,0.0020981679221451542,0.00017027932386840363

+16.636514,0.49101653695106506,-0.07423523813486099,0.66767418384552,-0.020198225228597474,0.001058893211260577,0.0013712405959346741

+16.6472229,0.4906651973724365,-0.07446500658988953,0.6670259237289429,-0.018582046958211456,-0.0002289962840718068,0.0027552455532611295

+16.6569831,0.4905933439731598,-0.07419011741876602,0.6670889854431152,-0.018779286007357086,-0.0007772522314459656,0.003046815463797928

+16.6678101,0.4902940094470978,-0.07428710162639618,0.6666198372840881,-0.018789993312448232,-0.0014773215067623963,0.003088580895411738

+16.6765032,0.49020057916641235,-0.07404795289039612,0.666632354259491,-0.019193521987007987,-0.0017238563982201933,0.0022117263221269924

+16.6882281,0.4899406433105469,-0.07406364381313324,0.6663300395011902,-0.019283123604050125,-0.001792009072379882,0.0017458600106355032

+16.6970045,0.48982900381088257,-0.0738542452454567,0.6662797331809998,-0.019605825084237843,-0.001532459276277563,0.0005946084223601387

+16.7087116,0.489595502614975,-0.07379903644323349,0.6659994125366211,-0.020449939670576123,-0.001214733844278147,-0.0001555503481820429

+16.7165511,0.48947036266326904,-0.07360804080963135,0.665922999382019,-0.020788216363087895,-0.0004686615474227215,-0.000898350667551282

+16.7272548,0.48925623297691345,-0.0735323429107666,0.6657496094703674,-0.021119932697534722,2.5573327411215185e-05,-0.0011416779739698314

+16.7370582,0.48912253975868225,-0.0733531042933464,0.6656767725944519,-0.021277970513830086,0.000506202180197718,-0.001168140407776594

+16.7480427,0.48893746733665466,-0.07321702688932419,0.665526807308197,-0.02057705552116976,0.0006934877554621899,-0.0008734670530412852

+16.7568146,0.48880064487457275,-0.07304101437330246,0.6654905676841736,-0.020789190893998208,0.0006481806879016332,-0.0006305598420012975

+16.7675506,0.48865577578544617,-0.07285328954458237,0.6654357314109802,-0.020124474797690493,0.00043004568963175155,-0.0007358621392695575

+16.7773062,0.4885197579860687,-0.07267503440380096,0.6654108762741089,-0.02037900206588925,-7.501765289390318e-05,-0.0008558124082048184

+16.7860901,0.4884026050567627,-0.07242459058761597,0.6652565598487854,-0.01886471337193636,-0.000754146615546808,-0.0011250838497972571

+16.7968309,0.48826804757118225,-0.0722372755408287,0.6652321815490723,-0.01910441362623998,-0.0011503992947649935,-0.0013937910951175713

+16.8065907,0.4881325662136078,-0.07204869389533997,0.6652219295501709,-0.01936409748744395,-0.0012709774960814372,-0.0019210461454852708

+16.8173222,0.4879958927631378,-0.07185839861631393,0.6652381420135498,-0.01975741250082129,-0.0010610968710128238,-0.002598339041256513

+16.8290346,0.4878580868244171,-0.07166578620672226,0.6652814149856567,-0.020118596511814232,-0.0004555733016756806,-0.0030468036222292202

+16.8368467,0.4877195954322815,-0.07147030532360077,0.6653510928153992,-0.020469179019596082,0.00011403722622229087,-0.0034614332116923367

+16.8466068,0.4875810146331787,-0.07127155363559723,0.665440559387207,-0.02075899784867587,0.000737108443873001,-0.003618120949548206

+16.8583145,0.4920715391635895,-0.06708448380231857,0.6691602468490601,-0.02100495773120183,0.0010148714868179719,-0.003723337841366513

+16.8661221,0.4920715391635895,-0.06708448380231857,0.6691602468490601,-0.02102276959794281,0.004806490066532912,-0.00882480327162497

+16.8778341,0.4927692115306854,-0.0655340850353241,0.6703521013259888,-0.021251929563953515,0.004260690215021272,-0.008707788807877002

+16.8866193,0.4927692115306854,-0.0655340850353241,0.6703521013259888,-0.021825652997411286,0.003946255276125277,-0.008932509385793784

+16.8964159,0.4929558038711548,-0.06492737680673599,0.6708635091781616,-0.02197720849565673,0.0027415977631542817,-0.008095854663995912

+16.9063222,0.4931458532810211,-0.0643124133348465,0.6713740229606628,-0.02210761789200695,0.0007898097373951095,-0.006597059531294436

+16.919837,0.49307680130004883,-0.06410901993513107,0.6713122129440308,-0.02115711364763355,-0.0018694594374412488,-0.003990364091362381

+16.9266675,0.49324458837509155,-0.06352275609970093,0.6717479228973389,-0.021311280183668388,-0.004241036130534248,-0.0017951872307812482

+16.9432593,0.493093341588974,-0.06340088695287704,0.6715924739837646,-0.021194462821338942,-0.009672570971152051,0.0032289099565031595

+16.9471891,0.4932224154472351,-0.06286010146141052,0.6720223426818848,-0.021194462821338942,-0.009672570971152051,0.0032289099565031595

+16.9588923,0.4930892586708069,-0.06232134997844696,0.6721954345703125,-0.021980617486989058,-0.013423850070562422,0.00699639096721139

+16.9696121,0.4930892586708069,-0.06232134997844696,0.6721954345703125,-0.021980617486989058,-0.013423850070562422,0.00699639096721139

+16.98328,0.4928410053253174,-0.062305860221385956,0.6718549728393555,-0.022946598021732538,-0.014671420939164492,0.008688669196343493

+16.9891336,0.49286124110221863,-0.061892494559288025,0.6721312999725342,-0.022970504175036443,-0.015120786040337517,0.009059227790836505

+17.0116189,0.49259987473487854,-0.06146266683936119,0.6720084547996521,-0.022740117010991902,-0.016349891068382805,0.010287913868451593

+17.013572,0.49259987473487854,-0.06146266683936119,0.6720084547996521,-0.022740117010991902,-0.016349891068382805,0.010287913868451593

+17.0193871,0.4922669231891632,-0.061118077486753464,0.6717278361320496,-0.022778637532663387,-0.017640601200175583,0.01097445772262554

+17.0292689,0.4922669231891632,-0.061118077486753464,0.6717278361320496,-0.022778637532663387,-0.017640601200175583,0.01097445772262554

+17.036956,0.49199599027633667,-0.06108079478144646,0.6712986826896667,-0.022723613764529662,-0.018757533147845513,0.011339765103786483

+17.0467488,0.4927063286304474,-0.06305065006017685,0.67137610912323,-0.02391209008700286,-0.020166016841118604,0.013583309745285778

+17.0574517,0.49275675415992737,-0.06291129440069199,0.6712349653244019,-0.024251005212548547,-0.02122293341525053,0.013012519783122614

+17.0672111,0.49232983589172363,-0.06387197226285934,0.6698294281959534,-0.025150139844609412,-0.023244615609525614,0.014093772318822938

+17.07602,0.4923127591609955,-0.06319931149482727,0.6702901124954224,-0.025332496888609373,-0.023989977977795347,0.013103168579497356

+17.0867637,0.4917466938495636,-0.06487293541431427,0.668738067150116,-0.026215058473381653,-0.025355762071537915,0.013378239421014286

+17.0965266,0.49188798666000366,-0.06333357095718384,0.6695280075073242,-0.026821006930069512,-0.025434016895803043,0.011777514193819918

+17.1075354,0.49101880192756653,-0.06520052254199982,0.6679186224937439,-0.02769468491553236,-0.02608134871726035,0.011125984372959872

+17.1172278,0.491281658411026,-0.06355268508195877,0.6685512065887451,-0.03029172816943124,-0.02579082157715756,0.009355134649596362

+17.1269887,0.4903697371482849,-0.06530638784170151,0.6670706868171692,-0.03071149409686586,-0.026316029845814697,0.008276497410161973

+17.1377254,0.49068790674209595,-0.0630907341837883,0.6682468056678772,-0.03120254632113442,-0.026404523245066813,0.005952484757653557

+17.1465332,0.4896763563156128,-0.06490809470415115,0.6667549014091492,-0.03135586704831464,-0.02741872346781115,0.005065562851784179

+17.1572491,0.4900052547454834,-0.06262212991714478,0.6679361462593079,-0.0312330317438859,-0.027824379400782938,0.0031970070682456764

+17.1670082,0.488886296749115,-0.06453989446163177,0.666335940361023,-0.031363829834297814,-0.029114412945353416,0.0028152378412401318

+17.1757879,0.48916909098625183,-0.06222361698746681,0.6675926446914673,-0.031350355522841065,-0.02965328304015265,0.0013746727674889584

+17.1865744,0.4880034923553467,-0.06414729356765747,0.6661083102226257,-0.03189683025885117,-0.031089434047418534,0.001441910340986511

+17.1962883,0.48819708824157715,-0.06236119195818901,0.6668826937675476,-0.03381205142754569,-0.03169430967439718,0.00024080983206033622

+17.2070245,0.4869883060455322,-0.0641217827796936,0.6654532551765442,-0.034036398057796464,-0.032740138897120116,0.00043665980104725955

+17.2152215,0.4871673882007599,-0.062122683972120285,0.6663697957992554,-0.035510680088900626,-0.032619815951332086,-0.0009210665102980771

+17.2269285,0.48594170808792114,-0.06379657238721848,0.6650508046150208,-0.03564049472768486,-0.03345367887965214,-0.0009967064068203244

+17.2366934,0.4852825999259949,-0.06384076178073883,0.6649363040924072,-0.03504855604196831,-0.03374775126478757,-0.0016977112067368023

+17.246503,0.48411786556243896,-0.06463588774204254,0.6638765335083008,-0.0354043819930879,-0.034465825062140514,-0.0016322826138763012

+17.2572241,0.48438531160354614,-0.06151549890637398,0.6655755043029785,-0.03632806812266537,-0.0337759284687264,-0.003743663633492283

+17.2659692,0.48316890001296997,-0.06295789033174515,0.664485514163971,-0.036159620603259376,-0.03476674138763758,-0.003107444238448759

+17.2764657,0.4831807017326355,-0.06061042845249176,0.6657655239105225,-0.036863207070978773,-0.03475732768393952,-0.004297687671224412

+17.2860707,0.4819035530090332,-0.062213022261857986,0.6647665500640869,-0.036560675841840626,-0.03639415463594906,-0.0036619151802723404

+17.2971475,0.48184919357299805,-0.06001047044992447,0.6660060286521912,-0.03689183569702768,-0.036977349278811786,-0.004834080428360774

+17.3059297,0.48044997453689575,-0.0616263747215271,0.6649613380432129,-0.036714188334699104,-0.03873612652065874,-0.003816321941524132

+17.3167391,0.48034146428108215,-0.059511613100767136,0.6661597490310669,-0.03697823477755552,-0.03968449664435621,-0.004689954463429767

+17.3264977,0.47887301445007324,-0.06110567972064018,0.6651657223701477,-0.03657767153950991,-0.041498417786675464,-0.0035004322637196502

+17.3362572,0.4779224991798401,-0.06099873036146164,0.6653125286102295,-0.03588590651928729,-0.04251775159528828,-0.0032360492906172945

+17.3460182,0.4763753414154053,-0.061746012419462204,0.6643399000167847,-0.03539409352812378,-0.04431391149303929,-0.0024901981695274133

+17.3567559,0.47643741965293884,-0.05834588035941124,0.6663707494735718,-0.035177824141539145,-0.04391509700207675,-0.004437670264626403

+17.3665133,0.4748575687408447,-0.05979446321725845,0.6653814911842346,-0.034817537074401786,-0.04529341503338223,-0.0032043223296077893

+17.377255,0.4737519323825836,-0.05961884185671806,0.6656032204627991,-0.03412046008070163,-0.045596958105881685,-0.003162971305104879

+17.3860665,0.47212153673171997,-0.06032371148467064,0.6647956371307373,-0.03353644903285026,-0.04628348438515194,-0.0025739604099451778

+17.3957939,0.4721183478832245,-0.056743789464235306,0.6669328212738037,-0.03251682404088152,-0.044615741344528656,-0.005339621219350861

+17.4065314,0.4703148603439331,-0.058081213384866714,0.6659963726997375,-0.03214769970907353,-0.04517432365092474,-0.0045363079254307406

+17.4164905,0.4690587818622589,-0.057830486446619034,0.6662192940711975,-0.03130725465510329,-0.04501807726762563,-0.004618192604902113

+17.4258111,0.4672672748565674,-0.058479879051446915,0.6653589606285095,-0.030430315435278483,-0.04573413417907822,-0.003544856167658831

+17.4365517,0.4658813774585724,-0.058275654911994934,0.6655014157295227,-0.029464584613265427,-0.046367040611999005,-0.003055984677319817

+17.4463075,0.46415412425994873,-0.05825447291135788,0.6648825407028198,-0.028424075792483766,-0.04748154438155168,-0.002121358608956534

+17.4560695,0.4626525342464447,-0.05805937573313713,0.6649953722953796,-0.027438376408665296,-0.04833118977715118,-0.001335130178544682

+17.4677816,0.4609833061695099,-0.057728204876184464,0.6645912528038025,-0.026497429196318346,-0.04939625580016716,-0.0006530626971709793

+17.4765633,0.4593789279460907,-0.057519372552633286,0.6646674275398254,-0.02546816190890888,-0.05046312720735639,4.930754447734007e-06

+17.4863234,0.4577687084674835,-0.05702964588999748,0.6644561290740967,-0.024561814563192032,-0.05138494462833018,8.222543051962328e-05

+17.4970591,0.45607221126556396,-0.05678847059607506,0.6644910573959351,-0.0234830318076132,-0.05223622124165217,0.0004181120966043

+17.5068223,0.45448827743530273,-0.05618789419531822,0.6643943786621094,-0.022572344976519092,-0.052576708897241906,8.165603865023172e-05

+17.5165807,0.45270493626594543,-0.055901557207107544,0.6644102931022644,-0.02149208404332224,-0.05293009180258614,0.00017179496319176519

+17.5263396,0.4511077105998993,-0.05522056296467781,0.6643938422203064,-0.020551062163681265,-0.05275110869294907,-0.0005138360308065358

+17.5370755,0.4492393136024475,-0.054883282631635666,0.6644302606582642,-0.019407078024982632,-0.052957686087356605,-0.0005634331206804042

+17.5468351,0.4475861191749573,-0.05414586514234543,0.6644800901412964,-0.018012034028668304,-0.05272092769517208,-0.0010763105280043941

+17.5576094,0.4484615623950958,-0.05116480961441994,0.6671862602233887,-0.018513970160585924,-0.049644023584678246,-0.004885793147964073

+17.5663556,0.4463268220424652,-0.051319196820259094,0.6666092276573181,-0.0175855644638166,-0.05036146155428361,-0.0035479772130547742

+17.5761153,0.44445618987083435,-0.05065884441137314,0.6668381690979004,-0.01624019684532636,-0.05086234646400267,-0.0024986402849889893

+17.585911,0.4422510862350464,-0.050715889781713486,0.6663376688957214,-0.014875802687572983,-0.05196254234551329,-0.00036749774684239397

+17.5966509,0.44025591015815735,-0.05008808523416519,0.6665396690368652,-0.013341414373988015,-0.05339834590191003,0.0018584880611552301

+17.6063711,0.43799257278442383,-0.0499085932970047,0.6662054061889648,-0.012021841253192334,-0.05545619082139192,0.0051823240536172195

+17.6166567,0.4358733594417572,-0.049311913549900055,0.6663833856582642,-0.01055058231970598,-0.05717520792802458,0.008109702506244033

+17.6254807,0.43352988362312317,-0.04901362955570221,0.6661540269851685,-0.009157962818821,-0.05910475339618579,0.011272110737409467

+17.6362176,0.43111860752105713,-0.04551218822598457,0.6688855886459351,-0.008885692189167146,-0.059444000381536924,0.01222174233996043

+17.6459361,0.42804479598999023,-0.04617143049836159,0.668031632900238,-0.0070696663698372655,-0.0607819622185401,0.015009927684389135

+17.6566721,0.42567530274391174,-0.0455501563847065,0.6681880354881287,-0.005534929838759644,-0.06103675189780669,0.016042798306028637

+17.6664326,0.42293214797973633,-0.045918580144643784,0.667466938495636,-0.0035849379187126167,-0.06108654964080037,0.017583954026162366

+17.6771685,0.4213640093803406,-0.0426529161632061,0.6691313982009888,-0.0035924488678961354,-0.05907272173735358,0.016703136152826537

+17.6859568,0.41870561242103577,-0.04388739541172981,0.6683951616287231,-0.0022169069601676835,-0.058688158922392514,0.018076115410860218

+17.6966876,0.4167419970035553,-0.04123876243829727,0.6694894433021545,-0.0023768430957423763,-0.05700424986003841,0.018089722179415815

+17.7074513,0.4138132333755493,-0.042788706719875336,0.6686890125274658,-0.0004360851284771434,-0.056854513122459024,0.019971964328418884

+17.7176148,0.4117782413959503,-0.0403631366789341,0.6696652770042419,-0.000437713060614746,-0.055939725970330284,0.02079844583108458

+17.7263982,0.40866583585739136,-0.042031627148389816,0.6688069701194763,0.0018880998636067682,-0.056575124345636885,0.023243021818985393

+17.7361588,0.4062563180923462,-0.039573922753334045,0.6698702573776245,0.002677559375327908,-0.05620774672579208,0.02451711656605011

+17.7459224,0.4029739797115326,-0.041213907301425934,0.6689819693565369,0.004523387055614149,-0.05669686511843235,0.027189631296979502

+17.7566591,0.40084847807884216,-0.03888789936900139,0.6698310375213623,0.004469740363777303,-0.0562849378315211,0.027803729630694468

+17.7664144,0.39746764302253723,-0.04068426042795181,0.6689525246620178,0.006481572143045107,-0.05678488024182721,0.02984710170284645

+17.7771502,0.3952694535255432,-0.03837808966636658,0.6697787046432495,0.0067380839339957746,-0.05603993795684127,0.029895001108515534

+17.7869145,0.39177748560905457,-0.040252551436424255,0.668891429901123,0.008868303254881731,-0.056702785737785026,0.03150578526201783

+17.7956991,0.38871222734451294,-0.03996561840176582,0.6691057682037354,0.010677959268669057,-0.057022115886329695,0.03172380025736587

+17.8064317,0.38498616218566895,-0.04109782353043556,0.6681339740753174,0.012424861693106736,-0.05773460831526746,0.03263061851038322

+17.816191,0.38307100534439087,-0.03795790672302246,0.6691539287567139,0.012698775829391924,-0.055772830999722314,0.030905216241540513

+17.8269311,0.3794611096382141,-0.03987628221511841,0.6682435274124146,0.014664950831866348,-0.05581997761599874,0.03197053258785872

+17.8357151,0.3761970102787018,-0.03972897678613663,0.6683772802352905,0.016498954902068253,-0.05533269644896209,0.03183551312682202

+17.8464462,0.3723803758621216,-0.04081214591860771,0.6674676537513733,0.018557391948855226,-0.0557346988817949,0.0325392640996912

+17.8562081,0.3689703047275543,-0.04079097881913185,0.6675254702568054,0.020206023394614726,-0.05540557155888498,0.03239652871455349

+17.8659713,0.3651844561100006,-0.04128677025437355,0.6668028235435486,0.02229748862295886,-0.05553901819471037,0.03268162611651722

+17.8757283,0.3633972108364105,-0.037976525723934174,0.6680294871330261,0.022863135055879814,-0.05219848505112825,0.02984589185651664

+17.8864672,0.3596448004245758,-0.03973403945565224,0.6671802401542664,0.024787658562920856,-0.051491752890747575,0.030488039060047652

+17.8972034,0.35688847303390503,-0.03729575499892235,0.6679648160934448,0.025141534049626168,-0.049269734527533374,0.028548064605846173

+17.9069583,0.3530568480491638,-0.03956390917301178,0.6671300530433655,0.02705420994246128,-0.048722313218307646,0.029252927007418876

+17.9158901,0.35020366311073303,-0.03738326206803322,0.6677744388580322,0.02745282901873497,-0.04696415275741971,0.027884722863188438

+17.9255301,0.34625667333602905,-0.03984376788139343,0.6669395565986633,0.029257371733791202,-0.04692435369542608,0.028871815243374073

+17.9362388,0.3432919383049011,-0.03788622468709946,0.6674976348876953,0.02956826986436958,-0.045946466419954486,0.027818119269185232

+17.9459986,0.3392621874809265,-0.04045847803354263,0.6666497588157654,0.031001802722254095,-0.046136787488853165,0.02910163721879916

+17.95578,0.3362481892108917,-0.038443151861429214,0.667212963104248,0.031555825130059126,-0.04506941065153477,0.02820153528723254

+17.9664993,0.3321273624897003,-0.04106585308909416,0.6663368344306946,0.033299558274065555,-0.045389028552882085,0.02937042354464142

+17.9772613,0.32903578877449036,-0.03911752253770828,0.666844367980957,0.03370261084561835,-0.0440747557680314,0.028307457522827758

+17.9869904,0.3248227536678314,-0.04189065843820572,0.6659363508224487,0.03540676745357936,-0.04392866425575463,0.028886986747419643

+17.996755,0.32155558466911316,-0.03996619954705238,0.666580080986023,0.03581596481394317,-0.042143852519277686,0.026938782744087206

+18.0074868,0.3172687590122223,-0.04277941584587097,0.6656839847564697,0.03723606646353127,-0.04164117203574031,0.02725786345155492

+18.0162751,0.313998818397522,-0.040808744728565216,0.6662361025810242,0.03758769625984001,-0.039596718165783855,0.025061933349346

+18.0260351,0.3096538186073303,-0.043687447905540466,0.6653505563735962,0.038805712520476515,-0.038887228691133355,0.025275046239001116

+18.0367711,0.3062796890735626,-0.04174232855439186,0.665937066078186,0.0386289794691395,-0.03685766219162741,0.02302308865672354

+18.0465316,0.3018950819969177,-0.0447046272456646,0.6651318669319153,0.039766500587756534,-0.03611855669498745,0.023150485620226348

+18.0553104,0.29845476150512695,-0.042752835899591446,0.6657456755638123,0.03923915174148841,-0.0340992586893235,0.020926232643635738

+18.0661714,0.2940426170825958,-0.04586135223507881,0.665058434009552,0.04005596230619957,-0.03340268110711968,0.021445617750995738

+18.075936,0.29060059785842896,-0.043946750462055206,0.6655891537666321,0.03946592539455598,-0.031237130387702705,0.0195920374281054

+18.0856973,0.28613895177841187,-0.04712865129113197,0.6649648547172546,0.03993826811938112,-0.030585352708110095,0.020102911686612976

+18.0954515,0.28264206647872925,-0.04521287977695465,0.6655233502388,0.039319668908963074,-0.028549206612881243,0.01797146286456228

+18.1061906,0.27810341119766235,-0.04844611883163452,0.6648722290992737,0.039772920386624666,-0.02785081011299544,0.01850443190153457

+18.1159673,0.2745596766471863,-0.046548906713724136,0.6654029488563538,0.0392297132739246,-0.025740078638130492,0.01627461236814649

+18.1257667,0.27002421021461487,-0.0498901829123497,0.6648496985435486,0.03957460807394876,-0.02499053523235337,0.016565366187903323

+18.1374713,0.266420841217041,-0.04797167330980301,0.6654167771339417,0.03856318442111611,-0.022895454631603026,0.013952680707268243

+18.1452276,0.26221391558647156,-0.04856386408209801,0.665570080280304,0.03832973615208489,-0.021657295311943898,0.012619934371407553

+18.1618222,0.2583152949810028,-0.04833483323454857,0.6656709909439087,0.03705910183868477,-0.018739257765891876,0.009008074363891314

+18.1657566,0.254095196723938,-0.04888978973031044,0.6658627986907959,0.03705910183868477,-0.018739257765891876,0.009008074363891314

+18.1813398,0.24998995661735535,-0.04929189756512642,0.6658969521522522,0.03596620605958656,-0.01711116902684502,0.007280158552217871

+18.1862209,0.24536718428134918,-0.05263777822256088,0.6656496524810791,0.03634114778668747,-0.016508791758508695,0.009090448457417855

+18.1959797,0.24104514718055725,-0.05345223471522331,0.6659149527549744,0.036026142855135605,-0.014809666832897136,0.007983487491336769

+18.2057402,0.23598361015319824,-0.0562705397605896,0.6654158234596252,0.036260990797434625,-0.014113335631702972,0.009235975182228998

+18.2174519,0.23286522924900055,-0.054637610912323,0.665729820728302,0.035043850259871966,-0.010591926979256773,0.0056223986390530585

+18.2262354,0.22854261100292206,-0.05545217916369438,0.6659772396087646,0.034719909439945316,-0.008636195248662812,0.004177877695385814

+18.2369758,0.22486498951911926,-0.05514524132013321,0.6660056710243225,0.034014818815158006,-0.005861351033291949,0.001097880088013595

+18.2467313,0.22058068215847015,-0.05587108060717583,0.6662352681159973,0.03388749639780998,-0.004127411701688036,-0.0012165986744632849

+18.2564922,0.21669958531856537,-0.05610109493136406,0.6661939024925232,0.03283864431159395,-0.0019505372122841068,-0.004160378693876712

+18.2662515,0.21244163811206818,-0.05676446855068207,0.6664049029350281,0.03275448576859841,-0.0004973421900571505,-0.006238135535492903

+18.2760115,0.2084507793188095,-0.05728825181722641,0.6662063002586365,0.031991608270957345,0.0012559734147596065,-0.00837366914314945

+18.285772,0.20421332120895386,-0.05791548267006874,0.6664189696311951,0.03183780727995863,0.002593325691313371,-0.009916713874305679

+18.2965448,0.1999775469303131,-0.05853337049484253,0.6666611433029175,0.031727974666698466,0.003915739536179622,-0.010822677497808379

+18.3062944,0.19574475288391113,-0.05914071574807167,0.6669273972511292,0.03152703035921145,0.005327278742874361,-0.011384762591616396

+18.3160532,0.19151628017425537,-0.05973673239350319,0.6672189235687256,0.03135666955617103,0.006764243436609881,-0.011641593483238556

+18.3257887,0.18729349970817566,-0.060321081429719925,0.6675263047218323,0.03118822589202192,0.008359454236760341,-0.01169806759443738

+18.3355476,0.1830778270959854,-0.06089367717504501,0.6678405404090881,0.031045889291237982,0.010085870626749725,-0.011738875081478872

+18.3463095,0.17887085676193237,-0.06145448982715607,0.6681557297706604,0.030907037901513938,0.011800420464520737,-0.011974503167140906

+18.3579965,0.1746741384267807,-0.06200345605611801,0.6684619188308716,0.03082210153362244,0.013572981530116929,-0.012371214435389594

+18.3667799,0.17048928141593933,-0.06254029273986816,0.6687533259391785,0.030661119529680113,0.015273934742697831,-0.013025169937752063

+18.3765405,0.16631801426410675,-0.06306438893079758,0.669034481048584,0.030514167470282676,0.016941391934160024,-0.013803782249556027

+18.3862999,0.16216212511062622,-0.06357486546039581,0.6693146824836731,0.030242801253166158,0.018651625716164914,-0.014692187542148454

+18.3970379,0.15802325308322906,-0.06407085806131363,0.669594407081604,0.02990293127009025,0.020457493993210448,-0.015499025983778747

+18.4067975,0.15390323102474213,-0.06455136835575104,0.6698805689811707,0.029501322760268355,0.02209634654997536,-0.016444803005953815

+18.4165567,0.14980384707450867,-0.06501542776823044,0.6701766848564148,0.02898167632349539,0.02404671215113856,-0.017050287052213908

+18.4263204,0.14572682976722717,-0.06546223908662796,0.670482337474823,0.028486507153897594,0.025871025077818577,-0.017467259168344556

+18.43608,0.14265739917755127,-0.06764581799507141,0.6640690565109253,0.027148662933856847,0.028043155769038916,-0.016512207790267384

+18.4458426,0.13863307237625122,-0.07213017344474792,0.6646864414215088,0.027546727202938014,0.029155422580672868,-0.014215920777394917

+18.4565724,0.1361410915851593,-0.07230013608932495,0.6640765070915222,0.026227065554600425,0.03216498228593081,-0.015603263491497371

+18.4653556,0.13174740970134735,-0.07436543703079224,0.6639338731765747,0.0264170388751308,0.03316022284102413,-0.015063830585189104

+18.4760929,0.12881535291671753,-0.07428167760372162,0.6633498668670654,0.025327436903553262,0.03561349047826924,-0.017687533062996773

+18.4858835,0.12459539622068405,-0.07659479975700378,0.6631770730018616,0.025559805587374515,0.03586411444029583,-0.018073739115749388

+18.4956551,0.12144135683774948,-0.07535789161920547,0.6625852584838867,0.02438585050712345,0.03756054044924202,-0.02125752560644585

+18.5063487,0.1174837276339531,-0.07832448929548264,0.662509560585022,0.024569849846192624,0.037586811918620115,-0.02240319471977105

+18.5161125,0.11424834281206131,-0.0763169378042221,0.6619703769683838,0.023109322630856237,0.03892845338506044,-0.025720181319510132

+18.5268437,0.11042573302984238,-0.07954829931259155,0.6619440913200378,0.02285082213523416,0.03886014192319732,-0.026712821968466558

+18.5356285,0.10726433992385864,-0.07714986056089401,0.6613382697105408,0.021480594587417114,0.04039322057774387,-0.029293959630543563

+18.5454135,0.10372628271579742,-0.07767236232757568,0.6612215042114258,0.020828395393566315,0.04132422780172083,-0.030571973588334925

+18.557118,0.10055453330278397,-0.0768435150384903,0.6607388854026794,0.01977579989863792,0.043024735274700715,-0.0321840175574854

+18.5669004,0.09684929251670837,-0.08053180575370789,0.6609798669815063,0.01950617737964668,0.04395055414769718,-0.031188741212137275

+18.5756716,0.09388899058103561,-0.07846224308013916,0.6605035066604614,0.018271374736691156,0.04608266671044796,-0.03279386451521524

+18.5854089,0.09027811139822006,-0.0818873941898346,0.6607540249824524,0.017342364873045364,0.04677996300005755,-0.03200830360355773

+18.5961826,0.08749096840620041,-0.07931199669837952,0.6601472496986389,0.016024467255985265,0.04897974594567641,-0.03331809781556703

+18.6069502,0.08393756300210953,-0.08263225108385086,0.6603413224220276,0.01563598087442421,0.04946185252277048,-0.0322700840133761

+18.6157466,0.08122570067644119,-0.07983677834272385,0.6597821116447449,0.01437544113164704,0.051072005897312776,-0.03356754741665002

+18.6258038,0.07782871276140213,-0.08314209431409836,0.6600978970527649,0.014590747823046816,0.050924232271904186,-0.03250581648280051

+18.6355646,0.07521293312311172,-0.08019839227199554,0.6595825552940369,0.013853370056977997,0.051593553343731224,-0.033966098714611925

+18.6452962,0.07187333703041077,-0.08345787227153778,0.6598678827285767,0.013724809382022557,0.050609288196002834,-0.033030408498777364

+18.6560377,0.06945302337408066,-0.08039925992488861,0.6592674851417542,0.012892398556614568,0.050992733105420664,-0.034626054178054165

+18.6667734,0.06617261469364166,-0.08362885564565659,0.6595677733421326,0.012910358843272138,0.0499863240906297,-0.03356473578104944

+18.6765327,0.06385301798582077,-0.08045292645692825,0.6590459942817688,0.012188524983279676,0.05070389670332455,-0.035098162031231867

+18.6853127,0.06066654250025749,-0.08365955948829651,0.659447431564331,0.012208698592532782,0.05031510812205405,-0.033633376889772366

+18.6960486,0.058437541127204895,-0.08042645454406738,0.6590504050254822,0.011351869338318612,0.05176820356618429,-0.03489578624620511

+18.7058091,0.055337004363536835,-0.08355622738599777,0.659555196762085,0.011206516185530126,0.051973843405173546,-0.03303167071735158

+18.7155697,0.05328426882624626,-0.0802273228764534,0.6590867638587952,0.010646359057040552,0.05368162921916729,-0.03389204484732696

+18.7263053,0.050213538110256195,-0.0832795575261116,0.6595203876495361,0.010949907540402362,0.05399346365494469,-0.031615579164765886

+18.7350891,0.048255305737257004,-0.07990157604217529,0.6590433716773987,0.01027823779328303,0.05552427522660739,-0.03269212924605981

+18.7458256,0.04527820274233818,-0.08293551951646805,0.6594868898391724,0.010169391726899875,0.055229363424704726,-0.030515233565076388

+18.7555856,0.04346359148621559,-0.07954932004213333,0.6589111089706421,0.009597530548737031,0.05612651009606022,-0.03140784106512186

+18.766325,0.0411391519010067,-0.07926920801401138,0.6591954231262207,0.009584273923445914,0.055850964269056474,-0.030571713933919522

+18.776081,0.039302192628383636,-0.07776618003845215,0.6587725877761841,0.009477436386893936,0.05597549611891819,-0.03055450243323253

+18.7858415,0.036314621567726135,-0.08102599531412125,0.6592814326286316,0.009658638088614162,0.05413997961235332,-0.02679231275376675

+18.7956179,0.0346597395837307,-0.07815635204315186,0.6588267683982849,0.00908614501379274,0.05405467719041939,-0.026887628995281496

+18.8053622,0.03189834952354431,-0.08098895102739334,0.659248948097229,0.009173675116703372,0.05216664861299151,-0.023381640540681203

+18.8170727,0.03033599816262722,-0.07758195698261261,0.6587162017822266,0.00893860014358009,0.05225016285849674,-0.02358860326249442

+18.8258607,0.027706658467650414,-0.0803455114364624,0.6590718030929565,0.009149866661874114,0.05108767533059257,-0.020095699316804945

+18.8356208,0.026199139654636383,-0.07677160948514938,0.6585029363632202,0.0084489021566713,0.051743862508345964,-0.020448563896893878

+18.8453816,0.02374500408768654,-0.07953118532896042,0.6588943004608154,0.008688830562063633,0.05111032172078957,-0.017343473424285175

+18.8561133,0.022277701646089554,-0.075816310942173,0.6583356261253357,0.00811281147275305,0.05222759509356114,-0.018275639517529373

+18.8658777,0.01997128315269947,-0.07865168899297714,0.6587886214256287,0.008374358481415684,0.052028834031668796,-0.015751167212708854

+18.8756377,0.018607057631015778,-0.07484044134616852,0.658193051815033,0.008013327520326149,0.05304123044111618,-0.016795162479611467

+18.8863727,0.016383711248636246,-0.07768962532281876,0.6586250066757202,0.008623766652572874,0.05226999141907234,-0.014123619313069503

+18.8961288,0.015095263719558716,-0.07385179400444031,0.6581340432167053,0.0085005966396717,0.052592740613092825,-0.014792596238233518

+18.9068695,0.012924076057970524,-0.0766213908791542,0.6584897637367249,0.0091646538755401,0.05104924104092902,-0.011783823725519879

+18.9156529,0.011727515608072281,-0.0726822093129158,0.6579946279525757,0.008747901938276608,0.0507939005441032,-0.012048725800005109

+18.9263849,0.009649889543652534,-0.07548590004444122,0.6583648324012756,0.009332005101902501,0.049115635371147236,-0.008626784125126442

+18.9351694,0.008542700670659542,-0.0715501457452774,0.6578349471092224,0.008566879880366536,0.04901252984698795,-0.00880008968919956

+18.9459047,0.006537864450365305,-0.07432965934276581,0.6581580638885498,0.008913719182469153,0.048155337884702616,-0.005420683588932184

+18.9556651,0.005514669232070446,-0.07036186754703522,0.6575999855995178,0.00855578724406904,0.04858472124766974,-0.006092866336378727

+18.9664006,0.0035768558736890554,-0.07318130880594254,0.6579108238220215,0.009283474304208323,0.04758636286436416,-0.0034265869401405836

+18.9761659,0.0025874534621834755,-0.06922109425067902,0.6574549078941345,0.008648382907915548,0.04810077072317263,-0.004405600401842374

+18.9859257,0.0007833729032427073,-0.07201654464006424,0.6578869223594666,0.008935190240359716,0.04728067097624568,-0.0016250554013938487

+18.9966578,-0.0002894985373131931,-0.06821399182081223,0.6578713655471802,0.008282799035136632,0.04777408260918403,-0.0023217011456208732

+19.0064244,-0.0022610207088291645,-0.07078230381011963,0.6583577990531921,0.008688424781984963,0.046857313406067316,0.0006840870361270211

+19.0152057,-0.002958758268505335,-0.06669045239686966,0.6576029062271118,0.008126583356237211,0.047414750406850635,-7.687187546602123e-05

+19.0259368,-0.004636173602193594,-0.06937134265899658,0.6580209136009216,0.008387236350840857,0.04602913033677774,0.002731411981981452

+19.0356979,-0.0053332033567130566,-0.06543466448783875,0.657417893409729,0.007554429804304158,0.04592747741108541,0.0016312416872565037

+19.0454985,-0.006915959995239973,-0.06822872161865234,0.657852053642273,0.008173873570100396,0.04446087389850706,0.0042052600254523335

+19.0552174,-0.007570423185825348,-0.0642433688044548,0.6573264002799988,0.007563625433862011,0.04447688310303246,0.002914296770618061

+19.0649768,-0.00907321460545063,-0.06708673387765884,0.657812774181366,0.007802931532230306,0.04333073023134313,0.005605054417304786

+19.0757178,-0.0096825510263443,-0.0630883276462555,0.6573619842529297,0.00724482242979127,0.043567070064667125,0.0046512926807201725

+19.0854767,-0.011097718961536884,-0.06593594700098038,0.6578795313835144,0.0077666975959664935,0.0425059713001604,0.0077345112173144385

+19.0952378,-0.011621684767305851,-0.06194387376308441,0.6574239134788513,0.007481844915237596,0.042760921722895105,0.007009109563342997

+19.1059737,-0.012958351522684097,-0.0648486539721489,0.657981276512146,0.007903135890152822,0.04146250182991057,0.010120625485152742

+19.1157337,-0.01344507560133934,-0.06092211976647377,0.657585084438324,0.007401111515650116,0.04146776310639055,0.009176329659568496

+19.1264649,-0.014742281287908554,-0.06384091824293137,0.6580881476402283,0.008000985705092075,0.040379175903098995,0.011963728823326506

+19.1352537,-0.015194658190011978,-0.05980850011110306,0.6577907204627991,0.007287480371360721,0.04058080935227113,0.010538933141025355

+19.1450089,-0.016395993530750275,-0.0627174973487854,0.6583969593048096,0.007935116196098126,0.039553394550656096,0.012797561030564784

+19.1557473,-0.016768615692853928,-0.05874485522508621,0.6581266522407532,0.007373583991964522,0.03968714793598077,0.011063380102043696

+19.1655056,-0.017914529889822006,-0.061639204621315,0.6587478518486023,0.007953450825722528,0.03851091996135236,0.013272154226240918

+19.1762419,-0.018202120438218117,-0.05775687098503113,0.6584736704826355,0.007420705152237766,0.03848603062986675,0.011640874382733661

+19.1860008,-0.019310498610138893,-0.06071637198328972,0.6590983271598816,0.00792404394915655,0.03680403138651461,0.01394608887535823

+19.1947848,-0.019552569836378098,-0.056825194507837296,0.6588931679725647,0.007206110649392663,0.036614458950613535,0.0125303189920146

+19.2064972,-0.020615126937627792,-0.05978800728917122,0.6595392227172852,0.007605457311484921,0.0350238704885162,0.01487749976127396

+19.2152857,-0.020781120285391808,-0.055956073105335236,0.6593608856201172,0.006840416556274446,0.034570645613912675,0.013242506646523126

+19.2250464,-0.02181979827582836,-0.05893000215291977,0.660031259059906,0.00750156927268863,0.03293966158273326,0.015579996624088517

+19.235777,-0.021938342601060867,-0.05512360483407974,0.6599236726760864,0.0066806941737053375,0.03281798633183107,0.013886500514326357

+19.2455562,-0.02296978421509266,-0.05804930999875069,0.6605410575866699,0.007249986309655142,0.03127009596277567,0.015984150397669518

+19.254323,-0.02302173525094986,-0.05433085560798645,0.6604043841362,0.0064374267645131685,0.03130754058341207,0.014176794030943962

+19.2650616,-0.02401782013475895,-0.057345107197761536,0.6610350608825684,0.00709696573285279,0.02987489640991623,0.016295740756520606

+19.2757928,-0.02418220415711403,-0.0538131482899189,0.6612387299537659,0.0065646169218870455,0.029961877113774467,0.014680346727863718

+19.2855528,-0.025387383997440338,-0.0566464401781559,0.6619076132774353,0.007306484271206437,0.028950589138918535,0.016460849248961275

+19.2953128,-0.02517048642039299,-0.05290209501981735,0.6614013910293579,0.00671148397504641,0.02952811736788958,0.014072277445980242

+19.3060539,-0.026172799989581108,-0.0558679960668087,0.6619386672973633,0.0072769001227436896,0.028012670594034294,0.015657235429358905

+19.3158137,-0.026049884036183357,-0.05212761089205742,0.6616113185882568,0.006380103133528715,0.027715240583445166,0.013529578222823989

+19.3251269,-0.026993002742528915,-0.05518234148621559,0.6621233224868774,0.00725554411944253,0.025800078214757338,0.015280959784700133

+19.335859,-0.02681712992489338,-0.05151252821087837,0.6617612838745117,0.0065337836462213235,0.02549886055322436,0.013147989936090662

+19.3446472,-0.027692623436450958,-0.054659921675920486,0.6623175740242004,0.007158031635974344,0.024569779410595207,0.015093108550413254

+19.3544102,-0.02753014862537384,-0.0510324090719223,0.6619989275932312,0.006392930615235666,0.02442383794593593,0.013154584280458265

+19.3661204,-0.02838936634361744,-0.0541929267346859,0.6624712944030762,0.006887113049991015,0.02284091377510143,0.015154795851300347

+19.3749488,-0.02816930040717125,-0.05059119686484337,0.662018895149231,0.006214787743390672,0.023180783450272767,0.013362364781971331

+19.3856615,-0.028951549902558327,-0.05379104241728783,0.6625070571899414,0.0066838624527084485,0.022242251022781778,0.015598059376352221

+19.3953944,-0.028736941516399384,-0.050173286348581314,0.662071704864502,0.00606877846498146,0.02287436994209919,0.013706444376471243

+19.4061334,-0.029499145224690437,-0.0534154437482357,0.6625014543533325,0.006411229880442425,0.021870536306436473,0.01548750994929627

+19.4149188,-0.029288358986377716,-0.0498034805059433,0.6620750427246094,0.005787542607694797,0.02226778785993612,0.013343293923265116

+19.4250399,-0.03001590445637703,-0.05309910699725151,0.6624854207038879,0.006414872862551644,0.021129974207694937,0.014973987793828273

+19.435776,-0.029775645583868027,-0.04956093057990074,0.662029504776001,0.005862529090698602,0.0213316191907346,0.01275774371971414

+19.4455407,-0.030477486550807953,-0.052818652242422104,0.6624016761779785,0.006464541366816148,0.020109757448028343,0.014592531534247201

+19.455321,-0.030242299661040306,-0.049253031611442566,0.6619961857795715,0.00576216527985354,0.02003765396229423,0.012525147830473779

+19.466143,-0.030942443758249283,-0.052581463009119034,0.6623344421386719,0.006658041749621672,0.018447520440795874,0.014402132597630889

+19.4748161,-0.03065919317305088,-0.04906333610415459,0.6618430614471436,0.005843815714385084,0.018468499413013647,0.012184299108763202

+19.4855524,-0.03131740540266037,-0.052410051226615906,0.6621940732002258,0.006556474208196647,0.01697707149341646,0.013848060316413705

+19.4962879,-0.031008215621113777,-0.048904772847890854,0.6616773009300232,0.005513025018838029,0.017420114273311596,0.011482053080776499

+19.5041136,-0.031694039702415466,-0.05227252468466759,0.661942183971405,0.006057623631175244,0.01633475912070077,0.013142608504691225

+19.5148324,-0.03137381374835968,-0.04880717769265175,0.661411702632904,0.00518771703163521,0.017107754368829338,0.011171512754109452

+19.5244526,-0.0320320799946785,-0.05224715918302536,0.6616935729980469,0.005581042509593048,0.016415200221941054,0.013226413249134211

+19.5352215,-0.03171265497803688,-0.04875309392809868,0.6611608862876892,0.004655400486696394,0.01698874577811648,0.011569779409439852

+19.5459574,-0.03237024322152138,-0.05219384282827377,0.661375105381012,0.005316293471417066,0.016218216003264136,0.01368491128110956

+19.5547435,-0.032070375978946686,-0.0486777238547802,0.6608846187591553,0.004101467162931204,0.016567839346702338,0.011121758823471566

+19.5655028,-0.03269710764288902,-0.05213622376322746,0.6611127257347107,0.005074426423988293,0.01569865847626121,0.013030835886073453

+19.5771894,-0.03237307816743851,-0.04864811897277832,0.6605769395828247,0.003525334553252222,0.015922286720374098,0.009277288426878522

+19.5849965,-0.032958950847387314,-0.052173566073179245,0.6608895063400269,0.004329125545320285,0.0150807979717062,0.011209229119867794

+19.5967174,-0.03317346051335335,-0.05203153192996979,0.6606401205062866,0.0028334501107521305,0.015481471895770064,0.007764721412399352

+19.6064686,-0.03318949043750763,-0.05218736082315445,0.6606776118278503,0.0035641098140869096,0.014634288301527118,0.009695358698941737

+19.6172063,-0.033377330750226974,-0.05208643525838852,0.6603555083274841,0.002444458936366591,0.015179353069079004,0.0072464668219441985

+19.6250137,-0.033378951251506805,-0.0522393099963665,0.6603943109512329,0.0030038516856047033,0.01411170991947722,0.009131742455298813

+19.6377,-0.03360498324036598,-0.05209434777498245,0.6601641178131104,0.0020751982352195807,0.01465692481361348,0.007205267304438592

+19.6455082,-0.03360498324036598,-0.05209434777498245,0.6601641178131104,0.0027736344875564185,0.013876537910702215,0.009164607055756408

+19.6572219,-0.03374764695763588,-0.052159201353788376,0.6600150465965271,0.0017440919789003416,0.014782375698508151,0.007066528046436861

+19.6650291,-0.03374764695763588,-0.052159201353788376,0.6600150465965271,0.0025923454044318862,0.014182623651232408,0.008744118336691436

+19.6767637,-0.03385091945528984,-0.05233757942914963,0.6599007844924927,0.0015768151447549967,0.014978800872261671,0.0065012027675251365

+19.6855474,-0.03385091945528984,-0.05233757942914963,0.6599007844924927,0.0022624913011587947,0.014023872280472265,0.008183502803068949

+19.698217,-0.03395845741033554,-0.05249304324388504,0.6598508954048157,0.0010453059063794657,0.014630727171913162,0.005997424085745575

+19.7040681,-0.03395845741033554,-0.05249304324388504,0.6598508954048157,0.00124505423039507,0.013828645401704172,0.007569792911695062

+19.714804,-0.03356398642063141,-0.049269597977399826,0.6593644618988037,5.6571021634784626e-05,0.014498147637353217,0.005279689514414475

+19.7255401,-0.03346386179327965,-0.04932156577706337,0.6594729423522949,-0.0003219105012707987,0.014424364325445293,0.004760942453152839

+19.7362766,-0.033049728721380234,-0.04809267818927765,0.6591258645057678,-0.0012816064658583682,0.014853024408476394,0.0029066241498976945

+19.7450601,-0.033753402531147,-0.05188869684934616,0.6596020460128784,-0.0008236179397332401,0.013794684269490742,0.005297506675683673

+19.7557986,-0.03333157300949097,-0.04939765855669975,0.6591978669166565,-0.0017772508972068763,0.014537382228856905,0.0032479884577092297

+19.7655568,-0.03318968787789345,-0.04946750029921532,0.6593021154403687,-0.001906518462373351,0.014615661269687984,0.003396443113202107

+19.7743408,-0.03276167809963226,-0.04850611835718155,0.6590170860290527,-0.002811689265028566,0.014756998000281116,0.002416872067835886

+19.7850758,-0.03256511688232422,-0.0485038086771965,0.6590840816497803,-0.0029652202142572237,0.014443968353930704,0.0024633387344235487

+19.7967878,-0.03291104733943939,-0.05201123654842377,0.6595413088798523,-0.0038454685523111047,0.014215280818191994,0.002233433425377451

+19.805574,-0.03291104733943939,-0.05201123654842377,0.6595413088798523,-0.003154404301361201,0.012391830000694338,0.005128713601585627

+19.8163088,-0.03318747505545616,-0.05323411524295807,0.6596634984016418,-0.004165387334717081,0.012458239188513487,0.003700892839622527

+19.8270741,-0.03304068744182587,-0.05349721387028694,0.6597636342048645,-0.0033532511030884673,0.010938868925889885,0.005985517665267994

+19.8338812,-0.032593779265880585,-0.05073784291744232,0.6593809127807617,-0.004311637337628343,0.011062491763845765,0.004148716627902326

+19.8446172,-0.032392170280218124,-0.05086969584226608,0.6594647169113159,-0.004482734816142133,0.010584371695224434,0.003909604576577363

+19.855354,-0.03190621733665466,-0.04970894008874893,0.6592268943786621,-0.005439509469569626,0.01051576160442833,0.0021133561417891874

+19.8651132,-0.03165765106678009,-0.049764472991228104,0.6592851281166077,-0.005599883655450761,0.010069565660516443,0.0011786847563017141

+19.8748731,-0.031269919127225876,-0.04944255203008652,0.659206748008728,-0.006366721243469677,0.00981342791143562,-0.00025272068671303085

+19.8846378,-0.030989861115813255,-0.04946783930063248,0.6592651009559631,-0.006434458926495373,0.009365347744616545,-0.0009047723980893645

+19.8943979,-0.030683200806379318,-0.049451325088739395,0.6593514084815979,-0.0071225671628869615,0.009131767719686289,-0.0013109379300187682

+19.9041541,-0.030382854864001274,-0.04947054386138916,0.659446656703949,-0.007108882097142763,0.009061001761268304,-0.001245960823622021

+19.914889,-0.03014964424073696,-0.049643926322460175,0.6595901846885681,-0.007829144887550894,0.008816184129292923,-0.0004215106906487754

+19.9252379,-0.03165470063686371,-0.0525679849088192,0.6601762175559998,-0.006634175340862831,0.006338580692769266,0.0050920374956500225

+19.9349981,-0.031101910397410393,-0.051645610481500626,0.660026490688324,-0.0074382414116054675,0.006432882762289411,0.004432237993940594

+19.9457743,-0.03192051127552986,-0.05469110235571861,0.660734236240387,-0.0059760239161185235,0.004221571202856403,0.007836790686684017

+19.9545589,-0.03142358735203743,-0.05269226059317589,0.6605128049850464,-0.0068574699346113915,0.004237087143552941,0.006467010470658953

+19.9652952,-0.031242845579981804,-0.05305783450603485,0.6608672738075256,-0.0070449782231817295,0.0038622759138978273,0.005664656154295896

+19.9750546,-0.030705194920301437,-0.052009325474500656,0.6607858538627625,-0.008063545081558111,0.004195169485382328,0.0029426657028234215

+19.9848148,-0.03048262931406498,-0.05230584740638733,0.6611456274986267,-0.008059867000683618,0.004362184274949465,0.0007025745540297812

+19.9955521,-0.029941130429506302,-0.0518503412604332,0.6611350774765015,-0.008987856602279437,0.00543078851943442,-0.0025535840926537733

+20.005314,-0.029681134968996048,-0.05209199711680412,0.661491870880127,-0.00897549075365562,0.006364955761064481,-0.00465267382924479

+20.0150706,-0.029155347496271133,-0.0519338957965374,0.6615818738937378,-0.009470522599453331,0.00692733710699286,-0.0068444321988484925

+20.0253627,-0.028860142454504967,-0.05212544649839401,0.6619471311569214,-0.009358334376089667,0.0071596465276139625,-0.0077309092334688165

+20.0341466,-0.028331102803349495,-0.052098553627729416,0.66202712059021,-0.009586548401424255,0.007565824528866427,-0.007933804969850985

+20.0448887,-0.028003158047795296,-0.05224870145320892,0.6623607277870178,-0.009468244964372154,0.007593297847925102,-0.00726665560585883

+20.0546446,-0.027473848313093185,-0.05230181664228439,0.6623571515083313,-0.010134756334357217,0.007797563561923759,-0.006508522671349668

+20.0644073,-0.027115965262055397,-0.05242396146059036,0.6626515984535217,-0.009987421811276952,0.007525992756057808,-0.005330902729111881

+20.0741665,-0.026680344715714455,-0.0526178777217865,0.6626340746879578,-0.010147394768621514,0.006946052567223999,-0.00403924662491396

+20.0849032,-0.026303205639123917,-0.0527360700070858,0.6628883481025696,-0.00997690516878031,0.005970538370055876,-0.003133372824537499

+20.0956399,-0.025864826515316963,-0.05293494462966919,0.6628744602203369,-0.010261179435915677,0.0048342013188886175,-0.002483784464570793

+20.1053995,-0.025472383946180344,-0.05305412411689758,0.6631225943565369,-0.010199796823819381,0.00401802972594302,-0.0022753934203062387

+20.1141789,-0.025059469044208527,-0.05333433672785759,0.6630277037620544,-0.010804367035935994,0.003265304177675203,-0.002105643426013947

+20.1249654,-0.024658819660544395,-0.05346464365720749,0.6632229089736938,-0.010669364882212174,0.0024417746430617907,-0.0025566637646432734

+20.1337035,-0.024255147203803062,-0.0537288561463356,0.6631691455841064,-0.01084641168586391,0.0015490473865157914,-0.0029036893314107613

+20.1444347,-0.023850593715906143,-0.053867071866989136,0.6633189916610718,-0.010660911697105856,0.0008783626586655323,-0.0034152996916234084

+20.1551719,-0.023463299497961998,-0.05416421592235565,0.6632400155067444,-0.010963428173671496,0.0002146033558602116,-0.003785335644836481

+20.164931,-0.023059550672769547,-0.05431101471185684,0.6633657217025757,-0.010634519724554163,-0.0003831395370012163,-0.0042001277406999655

+20.174691,-0.022659849375486374,-0.05459659919142723,0.6633109450340271,-0.010853450669206987,-0.0009704682240761969,-0.003950552447269055

+20.184454,-0.022258490324020386,-0.054748114198446274,0.6634653210639954,-0.01070126429162477,-0.0013892862392361747,-0.0036925145163855554

+20.1951866,-0.021864786744117737,-0.05504591390490532,0.6634236574172974,-0.011061284647151384,-0.0020115864275879187,-0.0031247833515761657

+20.2049474,-0.02146824635565281,-0.05520365759730339,0.6635648012161255,-0.010815774889323716,-0.0023507283291619085,-0.0028603405583523893

+20.2147111,-0.02105424925684929,-0.055519502609968185,0.6634631156921387,-0.010882307966774564,-0.0026186647575424864,-0.002682094186955718

+20.2244673,-0.020662982016801834,-0.05568517744541168,0.6635603904724121,-0.01054818095643451,-0.0029619426818282826,-0.002900443052803871

+20.2352027,-0.02025466039776802,-0.05601934343576431,0.6634290218353271,-0.010483626668387133,-0.0033329998486929255,-0.0029520019544769646

+20.2449678,-0.019832156598567963,-0.0562109611928463,0.6635074019432068,-0.010143513322822881,-0.003930618263360222,-0.002984269797711745

+20.2547228,-0.01941019296646118,-0.05653023347258568,0.6633448600769043,-0.010161870742452787,-0.004410837356339231,-0.002851643156314436

+20.2654624,-0.019033484160900116,-0.056710198521614075,0.6634284257888794,-0.010042242400979505,-0.005250964000479596,-0.003179917274718521

+20.2752234,-0.01859564706683159,-0.057024214416742325,0.6633145809173584,-0.010184529688761466,-0.006126081645195841,-0.0031941255647975424

+20.2840024,-0.01822744496166706,-0.057208102196455,0.6633760333061218,-0.009989598700912157,-0.006822320434838104,-0.0035424382154835665

+20.2937662,-0.01775631308555603,-0.05751007795333862,0.6631905436515808,-0.00987045219628237,-0.006877938616070661,-0.0035969002485188735

+20.3044991,-0.017396358773112297,-0.057694751769304276,0.6632149815559387,-0.009645267738888389,-0.007139031220546835,-0.00375639880082525

+20.3148755,-0.016966473311185837,-0.05800413340330124,0.663086473941803,-0.009598724698548965,-0.007044508245788682,-0.003768541136288677

+20.3246424,-0.016618477180600166,-0.05818996578454971,0.6631162762641907,-0.009391226645479624,-0.007119672530758946,-0.003780714327347962

+20.3353784,-0.016169682145118713,-0.058498118072748184,0.6630147695541382,-0.009798600931148952,-0.007161564298803813,-0.0037537772402401926

+20.3451383,-0.015832429751753807,-0.058683741837739944,0.6630815863609314,-0.009663325226045504,-0.007333252000807651,-0.00385071116314935

+20.3548941,-0.015379172749817371,-0.058982111513614655,0.6630046367645264,-0.009903122664955992,-0.007365049733320083,-0.00420436393581123

+20.3646537,-0.015051730908453465,-0.05916615575551987,0.6630833745002747,-0.009598074469827527,-0.007292797848876909,-0.004753761031178081

+20.3744138,-0.014616654254496098,-0.05948236212134361,0.6629979610443115,-0.009821403582801763,-0.007283783395159885,-0.0050815513720693034

+20.3841735,-0.014299942180514336,-0.05966512858867645,0.6630612015724182,-0.00954007174221127,-0.0074774339976989256,-0.005594381531230158

+20.3949143,-0.013853725045919418,-0.059992432594299316,0.6629848480224609,-0.009692859034785077,-0.00791851176498611,-0.006041110389416807

+20.4046707,-0.013547984883189201,-0.0601721815764904,0.6630927920341492,-0.00942951364985456,-0.008390434008120983,-0.006428499424934537

+20.4154115,-0.013090897351503372,-0.06044371426105499,0.6630708575248718,-0.009621477516830505,-0.008843599729928651,-0.006581387682828916

+20.4246924,-0.012794974260032177,-0.060614317655563354,0.6631955504417419,-0.009450291830534934,-0.009536293255433361,-0.006751852566953031

+20.434981,-0.012287234887480736,-0.060883425176143646,0.663112223148346,-0.00967267637839828,-0.009965841228392685,-0.006936011568525589

+20.4447826,-0.011999585665762424,-0.061043303459882736,0.6632035374641418,-0.009369791498363311,-0.010399795714058494,-0.007335088369409718

+20.4545785,-0.011497071012854576,-0.0613032691180706,0.6631590127944946,-0.009690701439234643,-0.010493250887976313,-0.007854972367267697

+20.4643044,-0.011220193468034267,-0.061450641602277756,0.6632540822029114,-0.009308892599716049,-0.01051494323836937,-0.008274909998910064

+20.4740848,-0.01068820059299469,-0.06175125390291214,0.6631903648376465,-0.009201425191876472,-0.010509859891307661,-0.008683885648240483

+20.4847986,-0.010421814396977425,-0.061887405812740326,0.6632803082466125,-0.008808234550373736,-0.010371750731112385,-0.008873084439494219

+20.4974875,-0.028903523460030556,-0.05262630805373192,0.6546257734298706,-0.007102518637978195,-0.017018648406898707,-0.007932619666953297

+20.5052965,-0.0292217880487442,-0.05267023295164108,0.6545478701591492,-0.006754192288881994,-0.017261758557139847,-0.007694070662204337

+20.515056,-0.028986088931560516,-0.05217110738158226,0.6539549231529236,-0.0073869691667042756,-0.0167362410545973,-0.008608026979309529

+20.5238399,-0.02928907796740532,-0.05213933065533638,0.6538262963294983,-0.0072199430587043196,-0.016395008166523194,-0.008453217865514192

+20.5346096,-0.029115300625562668,-0.051524583250284195,0.6533226370811462,-0.00794717222588057,-0.014207641740859336,-0.009067751452411768

+20.5443338,-0.029402997344732285,-0.05141349509358406,0.6531842350959778,-0.007740585078408313,-0.011546532455624705,-0.008482060056561153

+20.5571837,-0.031020380556583405,-0.05198199674487114,0.6527888178825378,-0.006246964853145733,-0.009692947964193552,-0.005866089950462461

+20.5645945,-0.03143598139286041,-0.05195816606283188,0.6527144312858582,-0.006096057574616354,-0.005750507523070154,-0.00453132870227788

+20.5769374,-0.03216784819960594,-0.05275930464267731,0.6523635983467102,-0.004532055183956029,-0.0025453838164621813,-0.002559772343984397

+20.5847549,-0.03262193873524666,-0.052744898945093155,0.6523131728172302,-0.004360215819046387,0.0009722748243887012,-0.0011964535705066273

+20.5974364,-0.033048115670681,-0.05285625159740448,0.6518681645393372,-0.002981158585978642,0.00402103356652014,-0.0002786713620117915

+20.6042458,-0.033498674631118774,-0.05282735079526901,0.6518511772155762,-0.0028772772784798543,0.006784595982956898,0.00040343770952208137

+20.6159834,-0.03383668139576912,-0.05236619710922241,0.6514953374862671,-0.0016486716951227306,0.009015798731702567,0.0005854191948102622

+20.6247576,-0.03426511213183403,-0.05232523754239082,0.6515253782272339,-0.0017379490966576256,0.01068081369938963,0.0006490656564613346

+20.6364762,-0.03448685258626938,-0.05181143060326576,0.6512055397033691,-0.00086521716171215,0.012222065782488412,0.00047721637134058836

+20.6442766,-0.03488093242049217,-0.05176666006445885,0.6512587070465088,-0.0010333910623067592,0.013309365597302808,0.00037282044874398067

+20.6579496,-0.03502853959798813,-0.05109025537967682,0.651033878326416,0.00019000436716352335,0.014373057244166577,0.0003526896560610732

+20.6647816,-0.03537822887301445,-0.05104108154773712,0.6511628031730652,5.607824395430907e-05,0.015322863563733741,0.0006124711463394904

+20.6764929,-0.03540046513080597,-0.05040685459971428,0.6508722901344299,0.0007865366204951986,0.016955312038808602,0.0012062467602720062

+20.6842676,-0.035696063190698624,-0.0503559373319149,0.6510992050170898,0.0006579086670419201,0.018188410913757128,0.0018901908796402336

+20.69598,-0.03564462065696716,-0.0497455969452858,0.6509209871292114,0.0016629061579208188,0.01983233047852283,0.0028147841495794724

+20.7047645,-0.0358794704079628,-0.04969523474574089,0.6512131690979004,0.001526259098098909,0.02150902894597334,0.003975726780546318

+20.7164756,-0.035783834755420685,-0.04913319647312164,0.6510631442070007,0.0022158134552508657,0.023174736250623777,0.005155298836028512

+20.7242843,-0.03595359995961189,-0.04908634349703789,0.651390552520752,0.0019414448905755906,0.024037954081802,0.006001070721532302

+20.7360292,-0.035749610513448715,-0.04854252561926842,0.6511955261230469,0.002153291395148554,0.024884261288163338,0.006619540250485994

+20.7448153,-0.03584735095500946,-0.048501137644052505,0.6515162587165833,0.0018879538435288344,0.02555839501728212,0.007138766448953335

+20.7555158,-0.035598985850811005,-0.048022665083408356,0.6513915061950684,0.0019514342502015742,0.026111798919384144,0.0070485081237111405

+20.7633237,-0.035624001175165176,-0.04798847809433937,0.6517155766487122,0.0017045470951233981,0.026066622548324016,0.006962956986763356

+20.7770479,-0.0353383868932724,-0.04753388464450836,0.651614785194397,0.0017656767663620043,0.026073879218676894,0.006651658286362601

+20.7838202,-0.035292234271764755,-0.04750574380159378,0.6519536375999451,0.0015479176242675777,0.025675497197632787,0.006573290669405361

+20.7975203,-0.03496309742331505,-0.046998053789138794,0.6518656611442566,0.001766952554037392,0.02543186783535823,0.006529407491477379

+20.8033395,-0.03484820947051048,-0.04697195440530777,0.6522242426872253,0.0015413549804107318,0.024828817270763796,0.006810022945648354

+20.8170049,-0.03445451706647873,-0.04656865447759628,0.652204155921936,0.0021763924055970755,0.024211876175478084,0.007082069954359283

+20.8257887,-0.03427281975746155,-0.04654798284173012,0.6526222825050354,0.0018521614277266568,0.023531498844166,0.007573675041721763

+20.8345985,-0.03348604589700699,-0.04308879002928734,0.6520721912384033,0.0007710799148622459,0.023632612194143164,0.006441089618324981

+20.8453082,-0.033199600875377655,-0.04295606538653374,0.6525155901908875,0.00041722718524160607,0.022735838753607174,0.006891252388656765

+20.8570209,-0.03303670883178711,-0.044707804918289185,0.6527656316757202,0.0009735142385791655,0.021624550620569182,0.008612698373808386

+20.8648416,-0.032730113714933395,-0.04468550160527229,0.6532334089279175,0.0008043250819848262,0.020764338869699507,0.009055278548202124

+20.8765698,-0.032368917018175125,-0.04488345980644226,0.6532507538795471,0.0011682865689724587,0.01975344926138,0.009824587217303865

+20.8843481,-0.0320226214826107,-0.04488744959235191,0.653729259967804,0.0009854879402291274,0.018581243063754815,0.010496625402772781

+20.896085,-0.031652819365262985,-0.04456060007214546,0.6537217497825623,0.00077661101266857,0.01742847699908209,0.010875525171980958

+20.9067953,-0.030770931392908096,-0.04144183546304703,0.6533781290054321,0.0005254688127212185,0.016142177410959486,0.011387901691267441

+20.9165851,-0.030841011554002762,-0.044251296669244766,0.6540536284446716,0.0006598340512071731,0.014727480124235923,0.011653849877882403

+20.9243688,-0.030425339937210083,-0.04427187144756317,0.6545339822769165,0.00045933743159793375,0.013186455126349302,0.011704093910083724

+20.9350996,-0.030023125931620598,-0.04392274096608162,0.6543669104576111,0.0007683502645711204,0.01185677973308868,0.011598306142852122

+20.9448647,-0.02958410233259201,-0.04395301640033722,0.654823899269104,0.0005570302620424094,0.010814368087412266,0.011420336167370577

+20.9546204,-0.028677018359303474,-0.04054009169340134,0.654532790184021,-0.0001804906432053335,0.010541188772403353,0.009453301059391092

+20.9643839,-0.028172090649604797,-0.040455255657434464,0.6549465656280518,-0.00029955384885682515,0.00959619170559748,0.009421179086905639

+20.9741462,-0.02724742330610752,-0.03888532146811485,0.6547405123710632,-0.0010405045100043094,0.009222376650613607,0.008218990073626753

+20.983899,-0.026687437668442726,-0.03872915357351303,0.655135989189148,-0.0011287259807500158,0.008176114658143005,0.008790138453141217

+20.9965871,-0.02712610550224781,-0.04134950041770935,0.6549552083015442,-0.0008538219932825753,0.005688757059117223,0.012538459551416367

+21.0034202,-0.02663675881922245,-0.041425012052059174,0.6553585529327393,-0.0009494997782565573,0.0045338641336761885,0.013523858107417712

+21.014156,-0.025629118084907532,-0.03929750621318817,0.6551163196563721,-0.0017031682018767088,0.003967330589429544,0.013020631495501839

+21.023916,-0.025086291134357452,-0.03927290812134743,0.655502438545227,-0.00184613040285293,0.002660968503686147,0.013936115233383787

+21.0346518,-0.024134140461683273,-0.03819591924548149,0.6553564667701721,-0.002523930205849571,0.0021438682992230168,0.013559948066205123

+21.0434358,-0.023552393540740013,-0.03811752423644066,0.6556972861289978,-0.0025319829384847095,0.0010835630727253,0.013989738388166563

+21.0541722,-0.022679463028907776,-0.03768797963857651,0.6555470824241638,-0.003077413017145606,0.0004446621848669843,0.01372481989354873

+21.0649082,-0.02207304537296295,-0.03759801760315895,0.6558729410171509,-0.003064555999188821,-0.0006308921839720191,0.014138830480880925

+21.0746681,-0.02146678790450096,-0.03752203658223152,0.6562206745147705,-0.003069969498629989,-0.002084853215745935,0.014231418043225896

+21.0844329,-0.020861955359578133,-0.03746021166443825,0.6565853357315063,-0.003097859952665302,-0.0034049593306315264,0.014476787582943743

+21.0941931,-0.020259900018572807,-0.037412598729133606,0.656959593296051,-0.0031791400741381817,-0.004533040014443915,0.014823969545278428

+21.1041453,-0.01966179721057415,-0.03737937659025192,0.6573358178138733,-0.0032629635733820075,-0.005256379881199987,0.015292056337712542

+21.114886,-0.019068483263254166,-0.03736073896288872,0.6577006578445435,-0.003359935709394193,-0.006045323162447007,0.015855567984743104

+21.1236654,-0.018480665981769562,-0.03735712170600891,0.6580507159233093,-0.003340713497584928,-0.006722724276367501,0.016483512012683815

+21.1344055,-0.017899174243211746,-0.03736937418580055,0.6584026217460632,-0.0034484766556706565,-0.007745406726187527,0.01717720847405046

+21.1441661,-0.017324911430478096,-0.03739826753735542,0.6587631702423096,-0.0035856126213381226,-0.008631572325823096,0.017745507636387457

+21.1548978,-0.016758840531110764,-0.03744445741176605,0.6591346263885498,-0.003757829122729349,-0.009588129410535766,0.017857635071661642

+21.164662,-0.02257418818771839,-0.042651500552892685,0.6562427878379822,-0.002540369373642851,-0.01533212833429307,0.023929749075076195

+21.1744176,-0.022343026474118233,-0.04327740892767906,0.6565200090408325,-0.002767946313261072,-0.0165169285472249,0.02328597775527916

+21.1841779,-0.02214951068162918,-0.043870940804481506,0.6567822694778442,-0.003017217446582429,-0.01698585399480995,0.022485227611340097

+21.1933459,-0.02197243645787239,-0.04448679834604263,0.6570408344268799,-0.0031514033560878923,-0.016921465080483693,0.021167162905297014

+21.2030982,-0.02181195467710495,-0.045123886317014694,0.6572930216789246,-0.003289826775868313,-0.016139600843276113,0.019229893634127644

+21.2147841,-0.021667635068297386,-0.04578059911727905,0.6575373411178589,-0.003481441492739888,-0.015100932122233013,0.016813625510057436

+21.2245727,-0.02153870277106762,-0.04645493999123573,0.6577813625335693,-0.003629257903334022,-0.013534220993895544,0.013818249745076913

+21.2352808,-0.02142403833568096,-0.04714442044496536,0.6580377817153931,-0.00377094503612037,-0.01142706601101489,0.010789137774018309

+21.2441658,-0.021321764215826988,-0.04784601181745529,0.6583046913146973,-0.0038966513816296147,-0.009434941191029406,0.007796023107660498

+21.2538489,-0.021229732781648636,-0.04855665564537048,0.6585686802864075,-0.004008565154228208,-0.007658661937216046,0.005279137217403019

+21.2645608,-0.02114606834948063,-0.04927365481853485,0.6588259935379028,-0.004034054862785064,-0.006334161210286822,0.003086234403575458

+21.2743209,-0.021069291979074478,-0.04999474063515663,0.6590837836265564,-0.004017116337570007,-0.0052519857796178345,0.0013642460073387348

+21.284085,-0.02099829912185669,-0.05071800574660301,0.6593595743179321,-0.0041011919875888975,-0.004797635482920552,-3.4853727068693866e-05

+21.294821,-0.020932361483573914,-0.05144187808036804,0.6596623659133911,-0.004140544430706273,-0.005064602802457391,-0.0012341949422487722

+21.3065286,-0.012795903719961643,-0.04213261604309082,0.6556385159492493,-0.004213595914248446,-0.005338702897695414,-0.0021624308185013413

+21.3145883,-0.012326513417065144,-0.042252302169799805,0.6557579636573792,-0.005757623702927515,0.0002563124976260569,-0.01141500692373751

+21.3243294,-0.011856659315526485,-0.04236111417412758,0.6558933854103088,-0.005825458872184894,-7.272805390762095e-05,-0.012647708143548183

+21.3350606,-0.010600260458886623,-0.04193286597728729,0.6555057764053345,-0.0068156748179930594,0.00029157132562617334,-0.014300977301437206

+21.3448254,-0.010090102441608906,-0.04197954759001732,0.65559983253479,-0.0066662554926123175,6.632612044816976e-05,-0.014506785175440757

+21.3536096,-0.009342368692159653,-0.041973721235990524,0.6554127335548401,-0.007182531535055341,-0.0003228546573889296,-0.013721401926033057

+21.3633655,-0.008818812668323517,-0.04198648780584335,0.6555013656616211,-0.0069548633833554025,-0.0015813226979101143,-0.011882868532679667

+21.3741057,-0.008307007141411304,-0.042112722992897034,0.6553792953491211,-0.007941401292949648,-0.003420442180895331,-0.009252970422898979

+21.3838615,-0.007787998300045729,-0.04211251810193062,0.6554723381996155,-0.007714027408730498,-0.00561873802475418,-0.006416348068028745

+21.3945973,-0.007433604449033737,-0.04231530427932739,0.6553085446357727,-0.00800970341160025,-0.008126234083423913,-0.0028960233804363024

+21.4034075,-0.006937031634151936,-0.04232456162571907,0.6554215550422668,-0.007910053970709046,-0.010212300474524589,-0.00023523315988159782

+21.4141412,-0.006682011764496565,-0.042571816593408585,0.6552229523658752,-0.00851521165642917,-0.012584998561784157,0.0022450303380627907

+21.4239159,-0.006221149582415819,-0.04260833561420441,0.6553086042404175,-0.008420758934122051,-0.013988124343277222,0.003508175497680124

+21.4336649,-0.006056070793420076,-0.04292232170701027,0.6551030874252319,-0.008891015352436782,-0.015182387178378191,0.004541366170922321

+21.4464366,-0.005914750974625349,-0.04324212297797203,0.6549248099327087,-0.008648794550465097,-0.015489569960205524,0.004544276324159184

+21.453157,-0.005536485929042101,-0.043354831635951996,0.6549585461616516,-0.00873086335594629,-0.015845854136190943,0.004843836397073824

+21.4668285,-0.00538594601675868,-0.04371107369661331,0.6548585295677185,-0.00871929493658433,-0.016033777929065247,0.0041171938786700715

+21.4726784,-0.0050248694606125355,-0.04387744516134262,0.6548802852630615,-0.00871929493658433,-0.016033777929065247,0.0041171938786700715

+21.4854012,-0.004870779812335968,-0.044233884662389755,0.6547890305519104,-0.008429657420861499,-0.01589446444881566,0.00369542245491001

+21.4941488,-0.00458909198641777,-0.044417258352041245,0.6548263430595398,-0.008628816363727056,-0.01611476247061056,0.003971730367214267

+21.5058665,-0.0043986476957798,-0.04477384313941002,0.6548421382904053,-0.008267145738645091,-0.01616831013299666,0.0040879647515268645

+21.5136735,-0.004158271010965109,-0.04498256742954254,0.654900848865509,-0.00865942094871535,-0.01644368482257059,0.004791538016230515

+21.5263611,-0.003991823643445969,-0.04534125700592995,0.6550010442733765,-0.008298443610833747,-0.016802018291762352,0.005131586789520885

+21.5331936,-0.003792921546846628,-0.04557359591126442,0.6551090478897095,-0.008559984613143048,-0.017255251330117106,0.005772681363027293

+21.5458773,-0.0035929426085203886,-0.04591260477900505,0.6552973389625549,-0.008262262270322064,-0.017830261712399764,0.00611857682233569

+21.554661,-0.0034325793385505676,-0.04616440087556839,0.6555166840553284,-0.008661101568158235,-0.018420712093716093,0.006095418702987604

+21.5654014,-0.003232187358662486,-0.04652787744998932,0.6557678580284119,-0.008313479414221399,-0.01850674130089058,0.0057303596366163854

+21.5732395,-0.0031090863049030304,-0.04679865762591362,0.6560549736022949,-0.008296176862842838,-0.01851896728614585,0.005244664684205574

+21.5858976,-0.002909756964072585,-0.04715770483016968,0.6563307046890259,-0.007811742404668518,-0.018410975584578625,0.004556822491593693

+21.5946774,-0.0028210480231791735,-0.04744269698858261,0.6566665768623352,-0.007974581996694173,-0.018092377249582875,0.0036382747749691955

+21.6044793,-0.0027506258338689804,-0.047731660306453705,0.6570228934288025,-0.007600804118865302,-0.017489839985228742,0.002852924215080648

+21.6132211,-0.0025551856961101294,-0.048149991780519485,0.6573079824447632,-0.007487278897431796,-0.016926595953886275,0.0022355717968525596

+21.6239575,-0.0025148214772343636,-0.048450201749801636,0.6576567888259888,-0.007145612649177334,-0.016411511130121313,0.0016165065556518721

+21.6346921,-0.0023139705881476402,-0.048848845064640045,0.6579377055168152,-0.0071224260383851695,-0.0160043475297127,0.0011774510696052718

+21.6442476,-0.0022991523146629333,-0.04915451630949974,0.6582749485969543,-0.006624046864140018,-0.015603407462682527,0.000843345708807009

+21.6532962,-0.0021248378325253725,-0.0495421327650547,0.6585864424705505,-0.006659393273438724,-0.015200497340714249,0.0005943157122177719

+21.6640367,-0.002134046284481883,-0.04985028877854347,0.6589110493659973,-0.006185182373214046,-0.01478876288564634,0.0002464778254959861

+21.6737918,-0.00197906163521111,-0.05020834878087044,0.6591873168945312,-0.006060724974455872,-0.014291436394599871,-0.0001221742150237348

+21.6845282,-0.002009488409385085,-0.05051535740494728,0.6594992876052856,-0.005687452913761499,-0.014120343677822899,-0.0004079612087897678

+21.6943674,-0.001875167596153915,-0.050884928554296494,0.6597874760627747,-0.005917517785409609,-0.014181091760965154,-0.0007804561413812481

+21.7050245,-0.001926027238368988,-0.0511903390288353,0.6600660085678101,-0.005442927102400589,-0.013886695827629272,-0.000978644188095639

+21.7138072,-0.0018055515829473734,-0.051523737609386444,0.6603174209594727,-0.005490385061602729,-0.013288666315472137,-0.0013574772860260648

+21.7255238,-0.0017026668647304177,-0.051826756447553635,0.6605637669563293,-0.0049523606003072426,-0.012660307349981085,-0.0018925225470418413

+21.7330512,-0.0017760676564648747,-0.05211931839585304,0.6608127355575562,-0.004606982604138527,-0.011932605640880455,-0.00246789054814951

+21.7457346,-0.0016381543828174472,-0.052492905408144,0.6610996723175049,-0.003991415147069404,-0.011342542417971006,-0.002885093926390157

+21.7535432,-0.001726717222481966,-0.052779290825128555,0.66133052110672,-0.0039109403578021385,-0.010595326972223937,-0.0033673552731708837

+21.7652549,-0.001643244526349008,-0.05309916287660599,0.6616176962852478,-0.0035108577842325782,-0.010170754856732803,-0.0033568469731033814

+21.7730641,-0.001756014535203576,-0.05340263992547989,0.6618531346321106,-0.0035300779244854855,-0.009668894641745451,-0.0036453234396167985

+21.785976,-0.0017253444530069828,-0.05368731915950775,0.6621242761611938,-0.0031637844468859005,-0.009482963047648172,-0.003992703129716047

+21.7937802,-0.0018412269419059157,-0.05395118147134781,0.662294864654541,-0.0032647220064304593,-0.009192046884039845,-0.004532399040981073

+21.8054926,-0.0018937767017632723,-0.05417415127158165,0.6625254154205322,-0.002850040663078722,-0.008919817581590012,-0.004926929434735399

+21.8142757,-0.002023535082116723,-0.05442288890480995,0.6626971960067749,-0.0027889307440068923,-0.008503433492655412,-0.0052490903277977695

+21.8260372,-0.02477610483765602,-0.04196179285645485,0.6521210670471191,-0.00021303342559482339,-0.014419420666909216,-0.004739882423606474

+21.8338811,-0.025469515472650528,-0.042039286345243454,0.6521036624908447,-0.000783824203436877,-0.013568979033672046,-0.005757981354143796

+21.8455613,-0.027093464508652687,-0.041877735406160355,0.6519012451171875,0.0017327336520576392,-0.014243163019961152,-0.003759676528478153

+21.8565706,-0.02835826762020588,-0.04413854330778122,0.6524230241775513,0.0010987216294112484,-0.011535772001909136,-0.004729232425450413

+21.8643707,-0.028915517032146454,-0.04161781817674637,0.6519037485122681,0.0038669094233933455,-0.009288813129256177,-0.0027520975677554757

+21.8741356,-0.029723521322011948,-0.0417364202439785,0.6519228219985962,0.0030492332653112592,-0.004482269612316676,-0.0028139716329906883

+21.8838948,-0.03075134940445423,-0.04447444900870323,0.6526345610618591,0.005358515970420789,0.0002795911666739475,-0.0007482942674325762

+21.8936508,-0.03126891702413559,-0.04135235399007797,0.6520073413848877,0.004650513119328477,0.00654162634227981,-0.0005401989740093117

+21.9053746,-0.031730636954307556,-0.039614591747522354,0.6514981389045715,0.004610738702738856,0.011685722832787685,0.000519996483566837

+21.9170747,-0.03239136561751366,-0.04295298084616661,0.6528053283691406,0.003869084607253419,0.016411020049903993,0.0003686895804143795

+21.92394,-0.03314991667866707,-0.043108586221933365,0.6530142426490784,0.0058725913734817975,0.019206555745996723,0.0022759610847300792

+21.9364401,-0.033412110060453415,-0.0433669351041317,0.6533539295196533,0.005080324340488401,0.022661111515577904,0.0014986730691261307

+21.9442488,-0.03410032391548157,-0.043538086116313934,0.6536330580711365,0.00689499837464243,0.024330860276337393,0.0026923817953121865

+21.9530302,-0.03420601040124893,-0.04055633023381233,0.6529093980789185,0.005935725978601736,0.02649352341968107,0.0015598957639078384

+21.9637413,-0.03485298156738281,-0.043547578155994415,0.6541382074356079,0.00798109256731785,0.02693197468940252,0.002850084726204205

+21.9754542,-0.03485631197690964,-0.04331714287400246,0.6542918086051941,0.006810718204243985,0.028309305234334513,0.002006656473472921

+21.9852129,-0.03478381410241127,-0.04024677723646164,0.6535200476646423,0.008659585780060599,0.028251664681116576,0.0037450854069700857

+21.9930215,-0.03520265594124794,-0.04035868123173714,0.6538649201393127,0.007492450794228841,0.029793531250338377,0.0030886950172389557

+22.0057116,-0.03510362282395363,-0.038783490657806396,0.6534219980239868,0.007261130142640534,0.030354076089965203,0.0036740376577285784

+22.0154703,-0.03530258312821388,-0.0422670841217041,0.6551459431648254,0.006382363548149733,0.031689281967020255,0.0030774802053587435

+22.025256,-0.03497672826051712,-0.03988999128341675,0.6545226573944092,0.007502436192977836,0.032064338565693115,0.005505404641402307

+22.0350145,-0.035222962498664856,-0.04294998571276665,0.6559715867042542,0.006796984172664567,0.03381336880929684,0.004392500131149285

+22.0457255,-0.03481382504105568,-0.040229059755802155,0.6553636789321899,0.008080749653278681,0.033786973455932595,0.006392415275979993

+22.055505,-0.03500755503773689,-0.043191760778427124,0.6566948890686035,0.007355443853885492,0.035079863755382655,0.005339878466570352

+22.0652457,-0.034538350999355316,-0.04034758731722832,0.6561717987060547,0.008394207050937743,0.03466723162301303,0.007299757337383057

+22.075029,-0.034667015075683594,-0.0433204248547554,0.6574488282203674,0.007481592507444284,0.03520630797904943,0.006007463060181527

+22.085741,-0.03411715105175972,-0.04038573056459427,0.6569489240646362,0.009010171506460017,0.033991689205607224,0.007761511650528199

+22.0955035,-0.034197308123111725,-0.04345611110329628,0.6581592559814453,0.008204388996242441,0.033440538856227955,0.006002742332595287

+22.1062625,-0.03360525518655777,-0.04044639319181442,0.6577702760696411,0.009627861610929076,0.031716860859256416,0.007336224664740029

+22.1150491,-0.03363165631890297,-0.04356912150979042,0.6589546799659729,0.008934701574997265,0.031119729673579108,0.005279665153288029

+22.1257576,-0.032939959317445755,-0.04052385315299034,0.6585358381271362,0.010037960679658503,0.02886766206117909,0.006602206459985429

+22.1355368,-0.03290511295199394,-0.04365520179271698,0.6596676707267761,0.009346680163872079,0.027980607927236438,0.004723796760343051

+22.1452776,-0.032196152955293655,-0.04059856757521629,0.6593563556671143,0.010464673618360905,0.025861922132763955,0.006244706850399838

+22.1550383,-0.032120876014232635,-0.04371406137943268,0.6604025959968567,0.00959508605014097,0.025163609958427917,0.004549303053557039

+22.1657978,-0.0313420332968235,-0.04064119607210159,0.6600363850593567,0.010689208381601829,0.023369102790087696,0.006248801901931824

+22.1755334,-0.031266987323760986,-0.04381021857261658,0.6609430313110352,0.009521113011734457,0.023084196830278143,0.004880980342288499

+22.1833416,-0.030876949429512024,-0.04405992105603218,0.6613640189170837,0.01090415479748271,0.0213893162140714,0.006674856470930636

+22.1940818,-0.030331723392009735,-0.04382903873920441,0.6614516973495483,0.010216328590721824,0.021010957256307077,0.004888657960013827

+22.2038375,-0.029891153797507286,-0.04407661035656929,0.6618543267250061,0.011438445849880137,0.019104024538692924,0.0065509370232834

+22.2155495,-0.029290633276104927,-0.043910879641771317,0.6619746685028076,0.010852078121570687,0.01815684395079637,0.004803378443466588

+22.2233573,-0.02880420722067356,-0.04415883123874664,0.6623718738555908,0.01200363223356575,0.015559137599915044,0.0063788459595989005

+22.2346798,-0.028243307024240494,-0.04398832470178604,0.6624200344085693,0.011326322631894167,0.014468292041904645,0.004770373426606297

+22.2444445,-0.02772403508424759,-0.044236667454242706,0.6628113985061646,0.012338057912375548,0.011740006614738927,0.0065337395910702355

+22.2541997,-0.02715424634516239,-0.044096048921346664,0.662997305393219,0.011722889517599594,0.01045060575548251,0.0046503059101198575

+22.2649399,-0.026188941672444344,-0.04089447483420372,0.6627072095870972,0.012879703064794162,0.00791166855736387,0.006130647754097649

+22.2756712,-0.02607167512178421,-0.044166743755340576,0.6633011698722839,0.013453073837933097,0.006233953851892672,0.0060250508838433515

+22.2854319,-0.02510920539498329,-0.0409436859190464,0.6630287170410156,0.013596580776873191,0.004813040483560926,0.005927620206983175

+22.2951914,-0.024980800226330757,-0.044223394244909286,0.6636123061180115,0.01269631458787003,0.004082457258786392,0.004073293198795089

+22.3059306,-0.024017751216888428,-0.04103212431073189,0.6633489727973938,0.013883578077837655,0.002149362329057948,0.0058755755266668855

+22.3147165,-0.023905299603939056,-0.044315844774246216,0.6638938188552856,0.0127365449908295,0.0016886799181470124,0.004104075012779952

+22.3255487,-0.022943349555134773,-0.04109686613082886,0.6636456251144409,0.013928374138844336,-0.0003837093833781629,0.006001656512539964

+22.3341057,-0.022860577329993248,-0.04435017704963684,0.6641272902488708,0.013150161477929688,-0.0010874813648676282,0.0042723153907062335

+22.3449642,-0.0219274815171957,-0.041127972304821014,0.6638903021812439,0.014432979284530162,-0.0031412154933699553,0.00594272710266274

+22.3536232,-0.02134084515273571,-0.041237495839595795,0.6641542911529541,0.013573709793753781,-0.003916039434222968,0.004303040563314999

+22.3653312,-0.02035582810640335,-0.039995837956666946,0.6639363169670105,0.01374302402031728,-0.005298995867833103,0.004572286097299101

+22.3760661,-0.02050263062119484,-0.04366480931639671,0.6643978357315063,0.014549572846985055,-0.007232500275741509,0.006266373939129799

+22.3849828,-0.01960155740380287,-0.04118292033672333,0.6641098260879517,0.014549572846985055,-0.007232500275741509,0.006266373939129799

+22.3956101,-0.019657498225569725,-0.044389162212610245,0.6644333004951477,0.015517525487176739,-0.009367276797946106,0.006969187461241707

+22.4053526,-0.01883614808320999,-0.04147518798708916,0.6641481518745422,0.01570533290769614,-0.01043239758992053,0.007467266270087625

+22.4160885,-0.018879087641835213,-0.044644102454185486,0.6644306182861328,0.015948576099084566,-0.011575758487590506,0.007783046870467678

+22.4248664,-0.01814134046435356,-0.04156193509697914,0.6642093658447266,0.01596232404225558,-0.012244128676871345,0.008007005930333579

+22.4353014,-0.01819101721048355,-0.04473809152841568,0.6644856929779053,0.016224749780803634,-0.012778202644966156,0.007944654187620496

+22.4450616,-0.017479760572314262,-0.041570305824279785,0.6642179489135742,0.01617920920005586,-0.013076460195619515,0.007961863588870889

+22.4557978,-0.01755344681441784,-0.04472281038761139,0.6644752621650696,0.016265498825269436,-0.013805562305937349,0.007290400831607247

+22.4655633,-0.016884228214621544,-0.04155414551496506,0.664216935634613,0.016285549109514044,-0.014119924974176296,0.006606009806994183

+22.4762936,-0.016990801319479942,-0.04474664852023125,0.6644845604896545,0.015421253916968743,-0.013496979306398147,0.004773846470317606

+22.4841042,-0.01664755493402481,-0.04501846432685852,0.6646706461906433,0.016936144156205514,-0.014620024160169198,0.005888396781666159

+22.4967903,-0.016410628333687782,-0.044819895178079605,0.66445392370224,0.01720607827793353,-0.015139785339561868,0.005505782403784124

+22.5036217,-0.01610327698290348,-0.04508773609995842,0.6646773219108582,0.01720607827793353,-0.015139785339561868,0.005505782403784124

+22.5143575,-0.015931684523820877,-0.04487977176904678,0.6645057201385498,0.01602695815786916,-0.015090862030705665,0.0038228792099499766

+22.5250993,-0.015256788581609726,-0.04169951006770134,0.6641342639923096,0.01730639602944917,-0.01628915083592737,0.005851094859967638

+22.5329061,-0.01496398076415062,-0.04182581230998039,0.6643546223640442,0.01633630317049519,-0.015737256557792487,0.004126579943208062

+22.5455909,-0.014320584945380688,-0.040522683411836624,0.6640146970748901,0.01629544264944473,-0.015741400731187016,0.0042240701539634756

+22.5535436,-0.014023431576788425,-0.04056372493505478,0.6641701459884644,0.015569594910664898,-0.015154895313308502,0.003166722520884387

+22.5661583,-0.013523831963539124,-0.040132489055395126,0.6639418005943298,0.015531191747894954,-0.014777986865969386,0.0033255433706123006

+22.5758453,-0.013896489515900612,-0.044085945934057236,0.6644501686096191,0.015310974226155776,-0.014627445662940658,0.004742266894438933

+22.5856114,-0.013299494981765747,-0.04184143990278244,0.6640958786010742,0.015310974226155776,-0.014627445662940658,0.004742266894438933

+22.5953653,-0.013985199853777885,-0.04503699764609337,0.6642667651176453,0.0156778252922466,-0.01482223166676972,0.005764846866713589

+22.6061014,-0.013279411010444164,-0.04239550977945328,0.6640583276748657,0.015616698644448304,-0.01440528782082034,0.0066339148316625456

+22.6148901,-0.013881812803447247,-0.04543635994195938,0.6641669273376465,0.015730110970600578,-0.014383644123085902,0.007683893403372459

+22.6256273,-0.013257661834359169,-0.04261161386966705,0.6639165282249451,0.01559260865909014,-0.014225157634541215,0.008597099217928424

+22.6353861,-0.013767431490123272,-0.04569944739341736,0.6641033291816711,0.015739696357925503,-0.014468089542008082,0.00895068287067566

+22.6461221,-0.013226190581917763,-0.04277786612510681,0.6638281941413879,0.015438709700553471,-0.014317214430580512,0.009172549868539003

+22.6568532,-0.013675348833203316,-0.04588867723941803,0.6640760898590088,0.015553127974297955,-0.014028952121581489,0.008292283743755426

+22.6666137,-0.013197274878621101,-0.04299682006239891,0.6637817621231079,0.015284884194562545,-0.013383358025328973,0.007408108714255989

+22.67247,-0.013197274878621101,-0.04299682006239891,0.6637817621231079,0.013892796315893623,-0.011969711507347382,0.004726911186968391

+22.6841874,-0.012709126807749271,-0.04176516830921173,0.6635534167289734,0.013522999307404495,-0.01126816697986624,0.003745502406790428

+22.6959048,-0.013430394232273102,-0.045434482395648956,0.6638872027397156,0.013114893859938585,-0.010970936948547439,0.004726188289161796

+22.7057837,-0.01296141091734171,-0.043183647096157074,0.6636161804199219,0.012857826363364308,-0.010119567230304695,0.004625513205812401

+22.7144379,-0.013532808050513268,-0.04634389281272888,0.6638545989990234,0.012996834998035615,-0.009468228834441548,0.005002067314028033

+22.7251739,-0.013102578930556774,-0.04365340620279312,0.6635241508483887,0.012721738384748623,-0.008864722626811327,0.00526010690621742

+22.7349381,-0.01363217644393444,-0.046739667654037476,0.6637172698974609,0.01297229637530651,-0.008549915788825694,0.0055709861387080225

+22.7456753,-0.013312293216586113,-0.0438704676926136,0.6634652018547058,0.01284329476958177,-0.008263745087483248,0.0060480642281106715

+22.7544556,-0.01383026409894228,-0.04699494317173958,0.6636478304862976,0.012856451369351998,-0.008166544996621809,0.005829079613089715

+22.7651953,-0.013486053794622421,-0.044084928929805756,0.6632554531097412,0.012591869587042314,-0.007741250184988529,0.005389092304416142

+22.774954,-0.013957832008600235,-0.04724555090069771,0.6635053157806396,0.012508843112953312,-0.007285673087330963,0.00466490107212364

+22.7847154,-0.013632629998028278,-0.044261444360017776,0.6630830764770508,0.012153030271363316,-0.006507206762934847,0.003818236296866223

+22.7944741,-0.014088723808526993,-0.047472208738327026,0.66335529088974,0.012662911593457178,-0.0056453206978687364,0.002887214120811088

+22.8052069,-0.013755954802036285,-0.044432926923036575,0.6628445982933044,0.012456714499528993,-0.004888764382970934,0.002107232584498552

+22.8139897,-0.014207089319825172,-0.04766743257641792,0.6631258130073547,0.01308641656479985,-0.004005476452304524,0.0013675854919178204

+22.8247314,-0.01387073379009962,-0.04463048651814461,0.6625193953514099,0.012878684197053196,-0.0027879324329679127,0.00107881470124114

+22.83449,-0.014283297583460808,-0.04787340760231018,0.6628673672676086,0.013428100717647589,-0.0016952492195926858,0.0009735447992533563

+22.8452273,-0.013990828767418861,-0.044836774468421936,0.6622990369796753,0.013117497652731791,-0.0008829092981672026,0.0010898636746641947

+22.8549817,-0.014401133172214031,-0.048098452389240265,0.6626673340797424,0.013206884849423514,-0.0002833605614137689,0.0012039341064813884

+22.8647418,-0.014028960838913918,-0.0450875386595726,0.6618742942810059,0.012855313022657331,0.00019137948651407635,0.0011983878562162444

+22.8745013,-0.014452445320785046,-0.04842459782958031,0.6622565984725952,0.012541793574034748,0.0006907143273260812,0.0011052738566855358

+22.8852434,-0.014111345633864403,-0.045334506779909134,0.6614652276039124,0.012212159904803283,0.0010063097722675148,0.000954400456297471

+22.8950011,-0.014501701109111309,-0.048624634742736816,0.6618854403495789,0.011962748689973265,0.0014552243870562822,0.0004943009171508056

+22.9057357,-0.014160600490868092,-0.04557060822844505,0.6611418724060059,0.011626738472830172,0.001729507951181571,2.860666477254075e-05

+22.9154936,-0.014522350393235683,-0.04885205253958702,0.6616086959838867,0.011705665755054995,0.0019173758344976563,-0.00042381909384078614

+22.9252743,-0.01416869554668665,-0.04582744091749191,0.6609219312667847,0.011368037004463224,0.0022837155995539433,-0.000608700537014725

+22.9340375,-0.01454575452953577,-0.049094557762145996,0.6613602042198181,0.011743830366517676,0.002371882370651113,-0.000760081688919411

+22.9457496,-0.014160503633320332,-0.046053510159254074,0.6607081294059753,0.011367340268926118,0.0027383334795811998,-0.0008972421728415508

+22.9535573,-0.01453955378383398,-0.04934050142765045,0.6611602902412415,0.011342205575998373,0.003045494941952637,-0.0012317046251559482

+22.9652741,-0.014096315950155258,-0.04623552784323692,0.6604950428009033,0.010985981764605392,0.0034803008091253197,-0.0015921207819040342

+22.9740534,-0.014510801061987877,-0.049531590193510056,0.6608900427818298,0.0108102522324298,0.003953324914364945,-0.002082854182551347

+22.9847941,-0.01399895828217268,-0.04640645161271095,0.6601252555847168,0.010500483205590274,0.004722924144933874,-0.002443051171395825

+22.9937424,-0.014434405602514744,-0.049685798585414886,0.6604852676391602,0.010723031696312762,0.0052726971759948175,-0.00300716209120922

+23.0054539,-0.013957151211798191,-0.04656316712498665,0.6598452925682068,0.010640547989223393,0.005641004371851966,-0.0032295339664281057

+23.014238,-0.014365860261023045,-0.049810104072093964,0.6602419018745422,0.010442173625470848,0.005933443401685034,-0.003208815100733493

+23.0249782,-0.013824135065078735,-0.046686965972185135,0.6595783233642578,0.010250686513115942,0.005627767176563014,-0.0027894649564449998

+23.0347353,-0.014229165390133858,-0.04993009939789772,0.6599799990653992,0.010803908289502546,0.005412579359056679,-0.002394996813683627

+23.0435183,-0.014215882867574692,-0.050109729170799255,0.6600601673126221,0.010558697474160583,0.00500293439767204,-0.0021975376576759647

+23.0552308,-0.014048993587493896,-0.05005970969796181,0.6597342491149902,0.010141841824526642,0.004499885612942118,-0.0022028972919574475

+23.0640189,-0.01401512697339058,-0.050244931131601334,0.6597970128059387,0.009773581886356476,0.0039677500204420525,-0.002447583665717969

+23.0737863,-0.013788512907922268,-0.0502176471054554,0.6594791412353516,0.009914365461446807,0.003978506595177172,-0.002844170929225351

+23.0854907,-0.013279219157993793,-0.04706127941608429,0.6587813496589661,0.008695261422982646,0.004756526122412172,-0.005143221435759917

+23.0932941,-0.013176923617720604,-0.047055989503860474,0.6587986350059509,0.008607360186161907,0.0049482491990576714,-0.0051433659394629905

+23.1050067,-0.01270571444183588,-0.0457424558699131,0.6582673788070679,0.008536206515645415,0.005176861282594386,-0.004912892813774929

+23.1128143,-0.01255833450704813,-0.04563279077410698,0.6582551598548889,0.007424322133556064,0.005792268547851798,-0.005770994502040087

+23.1245265,-0.012226345017552376,-0.04514636844396591,0.6579173803329468,0.007370548092837032,0.005384265459129318,-0.005248008813730298

+23.1342907,-0.012783522717654705,-0.04874442517757416,0.658613920211792,0.007290515193302461,0.00367436554479978,-0.0008073896429547673

+23.1450267,-0.012213967740535736,-0.0468844436109066,0.6580294966697693,0.007160652315943752,0.002781511277115699,0.0003184091590135313

+23.1538063,-0.012625357136130333,-0.04998978227376938,0.658475399017334,0.0068819994362636595,0.0015503083491704918,0.0021625949477316695

+23.1664988,-0.012128496542572975,-0.0474245510995388,0.65793776512146,0.005632781510303687,0.001242807110166956,0.0014415203311497731

+23.1733256,-0.01242423988878727,-0.050451673567295074,0.6583932042121887,0.0065820078162185935,-0.0002557915963260511,0.004290983369121187

+23.1840622,-0.011938595212996006,-0.047570064663887024,0.6578558683395386,0.006453445581297534,-0.000547976112659006,0.004538839916397855

+23.1939324,-0.012181813828647137,-0.05065229535102844,0.6583594083786011,0.00636896530416825,-0.0004911338053606433,0.004031553263839052

+23.2046726,-0.01172722689807415,-0.047591835260391235,0.6578709483146667,0.00629025951902893,-0.0003151081391486266,0.0029623242219056697

+23.213476,-0.011592532508075237,-0.0476573221385479,0.6579622626304626,0.005452154911915127,0.00038746381124034156,-0.0002913466210403442

+23.2251635,-0.011117633432149887,-0.04626872017979622,0.6576079726219177,0.005372176670620236,0.00023576499795798504,-0.0017110863391572976

+23.2339466,-0.010947943665087223,-0.0462401881814003,0.6577194929122925,0.004560216266485191,0.0007926622513051871,-0.0038653569228788817

+23.2456591,-0.010575310327112675,-0.045693814754486084,0.6575850248336792,0.0044549695851187,0.0007457853360741259,-0.004166095963979572

+23.2524908,-0.010384687222540379,-0.04561132937669754,0.6577401161193848,0.0038300695309036042,0.0010016044332667798,-0.004274691456798687

+23.2651788,-0.01005612127482891,-0.045399729162454605,0.6576108336448669,0.0038399466492654425,0.00047902722110238394,-0.0034012428829525375

+23.2739629,-0.009851658716797829,-0.04529143124818802,0.6577540636062622,0.0031443998227051752,4.882064143276319e-05,-0.0022511667439673788

+23.2856752,-0.009597060270607471,-0.04524797573685646,0.6576367020606995,0.003249601904361381,-0.0005722015876865282,-0.0005714506927036771

+23.2925075,-0.009388549253344536,-0.04514211788773537,0.6577596068382263,0.0027478828391519676,-0.001185418127700699,0.0013126975775835787

+23.3052005,-0.009167102165520191,-0.045130882412195206,0.6576886773109436,0.002958953029551417,-0.0019744535887959405,0.0029793120595539976

+23.3130024,-0.008959975093603134,-0.045039545744657516,0.6578139066696167,0.0021268489451434507,-0.0028100295107339746,0.0046849444950292154

+23.325691,-0.00881123449653387,-0.04513201862573624,0.6577721834182739,0.0022425180657163223,-0.0038340789156616553,0.005964759011669388

+23.334475,-0.009878681972622871,-0.047429267317056656,0.6583400368690491,0.00290439038546444,-0.00692714586487306,0.011610267815948044

+23.3452435,-0.009317630901932716,-0.046922359615564346,0.6581093072891235,0.0029821986016155063,-0.007581041503811689,0.012395409121590371

+23.3520664,-0.009209701791405678,-0.047113701701164246,0.6582515239715576,0.001911526527077158,-0.007221734212197087,0.011611834181778486

+23.3666832,-0.008764874190092087,-0.046652041375637054,0.6581470370292664,0.0009406447696066226,-0.006791716088164863,0.010505205461808923

+23.373515,-0.009545516222715378,-0.04884922876954079,0.6586796045303345,0.0024615125214176095,-0.007758788389189718,0.012305893458397974

+23.3862029,-0.009077430702745914,-0.047529928386211395,0.658301591873169,0.0015034311704632533,-0.006542704231930652,0.009290882989225807

+23.3930343,-0.00900848489254713,-0.047787610441446304,0.6584051847457886,0.001752006481003767,-0.005954871582573583,0.007593440991426739

+23.4066993,-0.008648639544844627,-0.046954263001680374,0.6582654118537903,0.0009382988048552387,-0.0047112088253670435,0.00483151375454458

+23.4135308,-0.008556608110666275,-0.04715753719210625,0.6583486199378967,0.0011359648894656992,-0.00408603080779031,0.003445407946213861

+23.4262188,-0.008246087469160557,-0.046697210520505905,0.6583662629127502,0.0005482293840893801,-0.0035112811908067066,0.001512761487174611

+23.4341064,-0.008882849477231503,-0.049067337065935135,0.6589916944503784,0.0021251126198860207,-0.005142802656203361,0.0037753240801185876

+23.4457425,-0.008497732691466808,-0.04769672825932503,0.6586753129959106,0.0011344532409564335,-0.004866380282359098,0.0027396627589295766

+23.4535468,-0.008961331099271774,-0.05036887153983116,0.6591849327087402,0.002806757714118556,-0.006216013747238038,0.005055334694061089

+23.4652587,-0.008701728656888008,-0.04809165373444557,0.6588945984840393,0.0018963818421850554,-0.005910371116064032,0.004122734721372582

+23.4720929,-0.008674140088260174,-0.04835548624396324,0.6589873433113098,0.001979563485814727,-0.006046501680934029,0.004176648883589557

+23.4857554,-0.008382251486182213,-0.047101788222789764,0.6588732004165649,0.0012581126367973224,-0.005379528842618928,0.0028355224590930856

+23.4935673,-0.008331436663866043,-0.047307904809713364,0.6590178608894348,0.0013965338817143096,-0.0049708430853001384,0.0022094009802476537

+23.506252,-0.008046709932386875,-0.046740129590034485,0.6590239405632019,0.0007138877757089275,-0.004068170118905433,0.0007398867799280236

+23.5140588,-0.008776934817433357,-0.049528125673532486,0.6596798896789551,0.0026806273498995864,-0.00551974432097502,0.0026787702826150408

+23.5247991,-0.008419127203524113,-0.047787804156541824,0.6594361662864685,0.002906292138996644,-0.005443243595796787,0.0022540625852714353

+23.5335786,-0.008990665897727013,-0.05064357444643974,0.6599670052528381,0.0038049274932963765,-0.005528309088476246,0.0021785306751434174

+23.5452912,-0.008687198162078857,-0.04808910936117172,0.6597193479537964,0.003787328855714519,-0.005544354880229197,0.0020894106127780565

+23.5540775,-0.009153022430837154,-0.05097155272960663,0.6602729558944702,0.004581412218540111,-0.005807707164330868,0.001905564087924654

+23.5657867,-0.008848137222230434,-0.04806261137127876,0.6599928736686707,0.004562384349619751,-0.00549176994948473,0.0017361386701714714

+23.5726076,-0.008872303180396557,-0.04829100891947746,0.6603150367736816,0.0036960571520392184,-0.004043403450047333,1.1611596771324897e-05

+23.5845664,-0.008498386479914188,-0.046870023012161255,0.6601132154464722,0.003587810956958631,-0.003489596964483201,-0.0003060062988446626

+23.5938716,-0.009098251350224018,-0.05013357102870941,0.6607915163040161,0.00427781536845331,-0.003119888576013347,2.672170818231881e-05

+23.6046077,-0.00868090521544218,-0.04765826091170311,0.6604406237602234,0.004340919358224281,-0.0023345609858106387,-0.00045207764679922757

+23.6133922,-0.009173092432320118,-0.05069226771593094,0.661065936088562,0.005180799768108266,-0.0018706030008342632,-0.00061007568008199

+23.6241272,-0.008758279494941235,-0.04784132540225983,0.6606651544570923,0.005269255388508169,-0.0017258423819934213,-0.0005110902586460901

+23.6329125,-0.009203910827636719,-0.05083753913640976,0.6612704992294312,0.006097851908065025,-0.0017678303735878707,-0.0005038488186918703

+23.6455996,-0.008819765411317348,-0.047829724848270416,0.6609020233154297,0.005337855372249426,-0.0010899241238304133,-0.002067488002236279

+23.6534086,-0.009287681430578232,-0.05086749419569969,0.6614318490028381,0.006771256606216986,-0.0016744342385127248,-0.0003445735089630563

+23.6661285,-0.008903935551643372,-0.04767893627285957,0.6610441207885742,0.0057909135481965315,-0.0007579183709895839,-0.0020352479199093744

+23.6729275,-0.009370200335979462,-0.05074012652039528,0.6615528464317322,0.006900196094580688,-0.001404469425914546,-0.0007678596949166552

+23.6856391,-0.008981495164334774,-0.04752042889595032,0.6611155271530151,0.00567680350500401,-0.0006274738848636657,-0.002926097111805348

+23.6934237,-0.009419660083949566,-0.05065261200070381,0.6616244316101074,0.00672934501545839,-0.0011939617628266876,-0.0017887779421537284

+23.7059702,-0.008998552337288857,-0.0473267063498497,0.6610733866691589,0.005605755574133665,-0.00021212220840135924,-0.0040349265641630005

+23.7130279,-0.009004883468151093,-0.04741448536515236,0.6612533926963806,0.005480080389246475,2.961077236863971e-05,-0.004172140340499064

+23.726289,-0.00859156809747219,-0.04594499617815018,0.6608244776725769,0.004354691832077083,0.0009443319933062754,-0.005410635640978565

+23.7331265,-0.008555537089705467,-0.045936789363622665,0.6609511971473694,0.004199731392164632,0.0012488993568833225,-0.004953025878461975

+23.7449887,-0.008248573169112206,-0.04529590159654617,0.6606897711753845,0.0034022818937903265,0.0018187227256815269,-0.005067675326740847

+23.7537957,-0.00900273583829403,-0.04867951199412346,0.6613184809684753,0.004716875623017912,0.000526878335760515,-0.0007182270870101258

+23.7664643,-0.008508647792041302,-0.04666653648018837,0.6608357429504395,0.00382969862869201,0.0009052959995616046,-0.0015580086083446711

+23.7732965,-0.009054379537701607,-0.04963385686278343,0.6613039374351501,0.005395465382398317,-0.0005352876190735263,0.0017862321530589058

+23.7859885,-0.008590555749833584,-0.046990685164928436,0.660740852355957,0.004306021077380735,-0.0004963895942743727,0.0011277600398458972

+23.7928208,-0.008569037541747093,-0.04705576226115227,0.6608028411865234,0.004148242755640259,-0.0011889601023028153,0.0018607599972529222

+23.8025808,-0.008548315614461899,-0.047122273594141006,0.6608480215072632,0.003869389097974762,-0.0020397993557182813,0.0020738831736922363

+23.8123364,-0.008529105223715305,-0.04719065874814987,0.6608656048774719,0.003697777627877656,-0.0023676300354550732,0.0020925643673466413

+23.8230776,-0.008511996828019619,-0.04726105555891991,0.66086345911026,0.003646467120593717,-0.0022261400840489273,0.001673223807484446

+23.8329456,-0.008497136645019054,-0.047333307564258575,0.6608614921569824,0.003551139911745712,-0.001879675253774079,0.0011711324198221441

+23.8423001,-0.00848428811877966,-0.047406964004039764,0.6608615517616272,0.00353668147493576,-0.001425154121955688,0.0007047675137711091

+23.8530362,-0.008473055437207222,-0.04748154431581497,0.6608600616455078,0.003507873020590381,-0.0008171151896999311,0.0005765086689059899

+23.8637719,-0.008462921716272831,-0.04755675792694092,0.6608601808547974,0.003513322529263217,-0.0005303575705795562,0.0008801951586888819

+23.8725571,-0.00845344364643097,-0.04763268679380417,0.6608564853668213,0.0034853274251866566,-0.0003520411336277169,0.0016400416707099894

+23.8842687,-0.010342367924749851,-0.050906162708997726,0.6605975031852722,0.0035019096358632207,-0.0007285638014041868,0.0026706623139847907

+23.8920762,-0.010461621917784214,-0.051272161304950714,0.660556435585022,0.005155960201322932,-0.0034663096996420833,0.007871943298429463

+23.9057404,-0.010780196636915207,-0.051767464727163315,0.6603010296821594,0.006749038304890163,-0.004338782676939362,0.009217358511942182

+23.9125771,-0.010917847976088524,-0.05216292291879654,0.660240888595581,0.006295312330530695,-0.004976067479559541,0.00965884166680069

+23.9252601,-0.01092817448079586,-0.05224314704537392,0.6600136756896973,0.007217934201199923,-0.005153006816485856,0.00882922756773468

+23.9321186,-0.011064574122428894,-0.05262617766857147,0.6599594950675964,0.006662607024360413,-0.004889301103200271,0.007681537680114649

+23.9458108,-0.010948819108307362,-0.05256563425064087,0.6596778631210327,0.00773499933555944,-0.0034328186021801593,0.004953199505784733

+23.9526148,-0.011073683388531208,-0.05291508138179779,0.6596116423606873,0.007232598379690123,-0.0020623730620316005,0.0026290900505633982

+23.9643283,-0.010870124213397503,-0.05278240889310837,0.6593132615089417,0.008210254778811087,-0.00033602190231636983,-0.0005848918344740342

+23.9721106,-0.010971730574965477,-0.05308171361684799,0.6592104434967041,0.007689711934813889,0.0009144250855539158,-0.002604059100953885

+23.9838295,-0.011083142831921577,-0.05340906232595444,0.6591038107872009,0.0071508496109926566,0.0018108752374431292,-0.004211023792369552

+23.992604,-0.011183040216565132,-0.05370310693979263,0.6590211391448975,0.006629476648883161,0.002306467825952524,-0.004987949367843745

+24.0023642,-0.011280881240963936,-0.053992483764886856,0.6589651107788086,0.006186828179518683,0.002382046935679941,-0.005225852989761957

+24.0121244,-0.011376376263797283,-0.05427666753530502,0.6589410305023193,0.005798985305108762,0.0020469142746259235,-0.004997315878353523

+24.0218892,-0.011469662189483643,-0.054555654525756836,0.6589516401290894,0.005460389318912484,0.0015032349763209336,-0.004415424235158517

+24.0326202,-0.011561200022697449,-0.054829902946949005,0.6589903235435486,0.005019687823867006,0.0008429272604346296,-0.0037336715936685124

+24.0434809,-0.011651613749563694,-0.05510016158223152,0.6590272784233093,0.004629153057795439,0.0001295267420870803,-0.0032793103921778624

+24.0522302,-0.011741559952497482,-0.05536704137921333,0.6590431332588196,0.004322587086481674,-0.0005553513821580241,-0.0032135651532769374

+24.0628811,-0.011831711046397686,-0.05563079193234444,0.6590413451194763,0.004094683819369308,-0.000816413866723355,-0.003633344247927442

+24.0736498,-0.01192254014313221,-0.05589121952652931,0.6590319275856018,0.003923322882228961,-0.00043161692045577975,-0.004465272918261661

+24.082434,-0.0120139941573143,-0.056147705763578415,0.6590162515640259,0.0038140430847987228,0.00032223283127095527,-0.005413427942923517

+24.0931771,-0.012105527333915234,-0.0563993901014328,0.6589932441711426,0.00374572986899429,0.0011560001256370061,-0.006293617284350005

+24.1029303,-0.012196365743875504,-0.05664537474513054,0.6589634418487549,0.0036841120357365255,0.0018797673216634574,-0.007004425343105705

+24.1127396,-0.01228577084839344,-0.05688494071364403,0.658918559551239,0.0036855686981837367,0.002440060251581462,-0.007457781534460204

+24.1224526,-0.01237313263118267,-0.05711754411458969,0.6588554382324219,0.003661032689891786,0.0026567069441181946,-0.007473332869388447

+24.1322377,-0.012458053417503834,-0.057342901825904846,0.6587806940078735,0.0036104426891218444,0.002457061742408281,-0.007217153322544751

+24.1429356,-0.012540527619421482,-0.057561155408620834,0.6586908102035522,0.0035423428662621106,0.002139865538128069,-0.006795539591614726

+24.1527457,-0.012620821595191956,-0.057772696018218994,0.6585754752159119,0.0034152982865272956,0.0017844415363632948,-0.006498260111552124

+24.1624672,-0.012699269689619541,-0.057977933436632156,0.6584247946739197,0.0032721855445566983,0.0017333841123479477,-0.006297589818109824

+24.1722459,-0.012776096351444721,-0.058177199214696884,0.6582245230674744,0.003140743779244104,0.0016811471301972233,-0.006452141155024307

+24.1829525,-0.01285133883357048,-0.05837049335241318,0.6579805016517639,0.003110513708864926,0.002009784711637071,-0.0067195883375824545

+24.1927514,-0.012924853712320328,-0.05855751782655716,0.657707691192627,0.0031429843305618974,0.0022019981533995133,-0.00714396905816809

+24.2025817,-0.012996380217373371,-0.058737918734550476,0.6574100255966187,0.0032217099412723753,0.002533715063915481,-0.00783269460213321

+24.2112556,-0.013065662235021591,-0.05891112983226776,0.6570923924446106,0.0032736614034875105,0.0030244538110057065,-0.008334681270858246

+24.2229679,-0.013132287189364433,-0.05907651409506798,0.6567617058753967,0.0034053959492098525,0.0033541950184156452,-0.008748930769973637

+24.2327271,-0.01319586019963026,-0.05923363193869591,0.6564170718193054,0.0036381319826470607,0.0035196040564950994,-0.00873293811062175

+24.2430966,-0.013256154954433441,-0.05938231199979782,0.6560553908348083,0.0037721234952304943,0.003685025264661682,-0.008890066459979277

+24.2528562,-0.013312986120581627,-0.05952242389321327,0.6556838750839233,0.003915123691381867,0.003479769622620177,-0.009029142117720202

+24.2626161,-0.013366363011300564,-0.05965379998087883,0.6553049683570862,0.0039781495826208225,0.003141857586077122,-0.009209829912673587

+24.273353,-0.01341654546558857,-0.059776272624731064,0.6549200415611267,0.004148963355675418,0.002576841810794602,-0.009208423747455317

+24.2811612,-0.013463963754475117,-0.05988971143960953,0.654533863067627,0.004202911592716991,0.0021101250137618983,-0.009144835762537091

+24.2918963,8.019116648938507e-05,-0.04177633300423622,0.6494660377502441,0.0016962597689738023,0.008315201142234588,-0.018476899117605475

+24.3016561,0.00060598662821576,-0.04107043147087097,0.6488680839538574,0.0018673085376015683,0.00779150105537815,-0.01845968958456805

+24.3114257,0.0011571788927540183,-0.040600862354040146,0.6480293273925781,0.0010918215548137405,0.007654795720353599,-0.0182597059892625

+24.3221866,0.0016523695085197687,-0.039931636303663254,0.6474362015724182,0.0015911585131658447,0.0073631689616852035,-0.01752279779802331

+24.3328882,0.0017517053056508303,-0.03947504609823227,0.6464930176734924,0.0013843092183997018,0.00621262213406987,-0.015056310343923823

+24.3433123,0.002240967471152544,-0.038798779249191284,0.6458228230476379,0.0020140300855657385,0.004343680314145387,-0.011891437764119925

+24.3520952,0.001991578610613942,-0.03833566606044769,0.6447117328643799,0.0019371201248194274,0.0009385404185609268,-0.006746009408954234

+24.3628665,0.0024493520613759756,-0.03768205642700195,0.6439839005470276,0.0025691505648536652,-0.002309641044797463,-0.0014524588543628587

+24.3726252,0.0020091296173632145,-0.03724826127290726,0.6427798867225647,0.002299619198899027,-0.006866351799920303,0.0048165527930705485

+24.3823527,0.0024122376926243305,-0.03664952516555786,0.641995906829834,0.0028492141750692166,-0.010458124811134582,0.009850666221566003

+24.3930882,0.0019037870224565268,-0.03635593131184578,0.6407224535942078,0.0023035685992547463,-0.014452815411219113,0.015281364818091175

+24.400922,0.002233597682788968,-0.035843051970005035,0.6398577094078064,0.002922250122824641,-0.01709842155120096,0.018611642330321216

+24.4126084,0.0018406385788694024,-0.03570612147450447,0.6386274099349976,0.0026182397863253886,-0.019637240546601424,0.022137642511691334

+24.422367,0.00209177122451365,-0.03529239818453789,0.6376938223838806,0.0032239611122473442,-0.020708220772398464,0.023433338115353558

+24.4331039,0.0018372847698628902,-0.035287678241729736,0.6364513039588928,0.0029938952974733262,-0.021560295785629013,0.02475574419964306

+24.4426506,0.0020140118431299925,-0.034975506365299225,0.6354796290397644,0.0038401575684326506,-0.02128009465874742,0.024522502052539655

+24.4527315,0.0018954549450427294,-0.03508797287940979,0.6343376636505127,0.003804757299882182,-0.020905189101088104,0.02478991140784841

+24.4634567,0.0020064297132194042,-0.034869372844696045,0.6333033442497253,0.004727382131890564,-0.020212990741471686,0.024342980068560848

+24.4722393,0.0020641107112169266,-0.035097721964120865,0.632228434085846,0.00468003752391821,-0.020016979051103313,0.02497068470043535

+24.4819992,0.002121313940733671,-0.03496411070227623,0.6311551332473755,0.0056590698873092565,-0.019692455388083646,0.025059804952867443

+24.4927398,0.002276864368468523,-0.035245131701231,0.6300045251846313,0.005700334321958352,-0.019926286023228098,0.02611175236000647

+24.5015242,0.002286926144734025,-0.035192303359508514,0.6289045214653015,0.006864207981889425,-0.020083511943419976,0.02666063032824913

+24.5122598,0.0024702877271920443,-0.035510916262865067,0.6278296113014221,0.007151901933317196,-0.020385726902887556,0.02744227938091467

+24.5220158,0.0024402879644185305,-0.03553159162402153,0.6266990303993225,0.008154858636009722,-0.020532492169648208,0.027591563160135373

+24.5327509,0.0027734870091080666,-0.03601568192243576,0.6251119375228882,0.008378191041279539,-0.020712546912315263,0.027839339080230414

+24.5415357,0.0027106141205877066,-0.036116793751716614,0.6239129304885864,0.009527938771240413,-0.020605088525993576,0.027350939673379357

+24.5522737,0.003129572607576847,-0.036696553230285645,0.6226527690887451,0.009381556922592524,-0.019986455718497154,0.026698625336349167

+24.5630085,0.0030399456154555082,-0.03686877712607384,0.6213672161102295,0.010544090338730447,-0.019576702999363323,0.025369278903924545

+24.5737463,0.003506207372993231,-0.03752978891134262,0.6201152205467224,0.010764415995626022,-0.0188308801462639,0.024303909838515717

+24.5825298,0.003393018851056695,-0.037767231464385986,0.6187546849250793,0.01203315137086552,-0.018403256920619775,0.02305208189584467

+24.5932639,0.0037081215996295214,-0.03834286332130432,0.6173977255821228,0.01278683023067949,-0.017930250983376243,0.021985769226051936

+24.6039987,-0.002712137531489134,-0.03720780834555626,0.6135042905807495,0.016298992343300588,-0.020658665384956865,0.023307439240993034

+24.6118075,-0.0025832378305494785,-0.037187255918979645,0.6116697192192078,0.016364825294267145,-0.01957671908423282,0.021359719602061563

+24.6235192,-0.0039470000192523,-0.03868991136550903,0.6102420687675476,0.020094384764383952,-0.020635561877181408,0.022237177044018317

+24.6323036,-0.003918459173291922,-0.03773036226630211,0.6081671714782715,0.020311365740204385,-0.019106273583012458,0.020247606342547082

+24.6440341,-0.004845358431339264,-0.040177278220653534,0.606817901134491,0.02379284268970493,-0.018911149223454198,0.020150888306132913

+24.6528181,-0.005012510810047388,-0.03818267956376076,0.6046949625015259,0.023695310124684402,-0.016953095154581627,0.01791914373891708

+24.6626664,-0.00551867438480258,-0.03876276686787605,0.6030647158622742,0.024560512167040686,-0.015331846150641433,0.01623862796568634

+24.6713616,-0.005698387511074543,-0.037554070353507996,0.6009547710418701,0.02442140917345342,-0.01291134590636751,0.013567435840230149

+24.6830971,-0.007056157570332289,-0.04096139222383499,0.5987067222595215,0.02781427624624016,-0.011011349635957457,0.01175829665636332

+24.6918576,-0.006833525840193033,-0.03782201558351517,0.598443329334259,0.026993047456380096,-0.010408741026005882,0.010834172097580074

+24.7025937,-0.008304044604301453,-0.041530411690473557,0.5950371026992798,0.030707028157847552,-0.0071370150999199,0.008413489311299576

+24.7123536,-0.00803825818002224,-0.037995751947164536,0.5946528911590576,0.029769178238296726,-0.00650998792380953,0.007491577233179921

+24.72309,-0.009428310208022594,-0.04179265722632408,0.591257631778717,0.03252303053532877,-0.005430291260879315,0.0068831977542967385

+24.7318742,-0.009023639373481274,-0.038164060562849045,0.5907070636749268,0.032396423048600416,-0.0035282247260819055,0.004801789387524781

+24.743601,-0.009836110286414623,-0.041428644210100174,0.5891008377075195,0.03503263960096171,-0.003144580397545084,0.004511829703769176

+24.7523999,-0.0099201500415802,-0.03844144567847252,0.5865707993507385,0.0349163053353563,-0.0018270523975783244,0.002551859921039025

+24.7631488,-0.010694521479308605,-0.04173680767416954,0.584965169429779,0.0373347940094709,-0.0014586965244175664,0.002363165010013968

+24.7709307,-0.01070357859134674,-0.03876420855522156,0.5823071002960205,0.037135974783107754,6.213437886353152e-05,0.00016870370546902058

+24.7816983,-0.011223044246435165,-0.03930552676320076,0.5802545547485352,0.03786476737514338,0.0008721152562125602,-0.0009693607832574462

+24.7924292,-0.011246045120060444,-0.03791467472910881,0.5775322914123535,0.03731345686895677,0.003004878390481686,-0.0031497973830594394

+24.8031415,-0.01242307759821415,-0.04222936928272247,0.5738162994384766,0.039702881875499876,0.005627155454642084,-0.0037775085853804283

+24.8119208,-0.011920981109142303,-0.039204031229019165,0.573158323764801,0.03889280729074243,0.0064794585463249085,-0.005110092444914504

+24.8226615,-0.012995125725865364,-0.0431513786315918,0.5692282319068909,0.04117858876401376,0.008836857503339993,-0.00484345502854109

+24.8324215,-0.012500898912549019,-0.03969190642237663,0.5685403347015381,0.04009271374326634,0.009693252767726007,-0.0062596124706335785

+24.8431528,-0.013094861060380936,-0.043014805763959885,0.566703200340271,0.04225374093395604,0.01018928472296685,-0.0052633297954165345

+24.851941,-0.012919061817228794,-0.03995908424258232,0.5636782646179199,0.041608742393498606,0.011353121708300691,-0.006925784319854904

+24.8626775,-0.013564175926148891,-0.043314993381500244,0.5616955161094666,0.04409536081431294,0.010993640194167834,-0.006107701236618958

+24.8724344,-0.013273748569190502,-0.04025014489889145,0.558569610118866,0.04361664194636256,0.01156873693826565,-0.007981949918434735

+24.8821928,-0.013915167190134525,-0.043593838810920715,0.5565303564071655,0.045602461219375605,0.010787729934601179,-0.007218917443675861

+24.8919528,-0.013580121099948883,-0.04045892506837845,0.5533892512321472,0.045354874236181786,0.010949621200520196,-0.009170424839991628

+24.9026933,-0.014217494055628777,-0.04376743733882904,0.5512217879295349,0.04761049083004374,0.009978916572323969,-0.008391593649834505

+24.9114738,-0.013839398510754108,-0.04066082090139389,0.5480049252510071,0.047251599674509794,0.010387856788505585,-0.01016436432970813

+24.9222101,-0.014794635586440563,-0.044394854456186295,0.5429850220680237,0.04926371482248461,0.009673318434871693,-0.008968244390911914

+24.9319689,-0.014305789023637772,-0.04107293114066124,0.5396161675453186,0.04876628642638288,0.010202938600119211,-0.010301082386469672

+24.9432146,-0.015016213990747929,-0.04448987543582916,0.5371577739715576,0.050690801718637914,0.009521930898842854,-0.0085019437398109

+24.9530818,-0.014516323804855347,-0.04117685183882713,0.5337544083595276,0.04999383529322562,0.010114079039254077,-0.00942168375656731

+24.9628491,-0.015226567164063454,-0.04457993060350418,0.5311835408210754,0.05183227319521833,0.009418835903655743,-0.007370599325014183

+24.9725791,-0.014692545868456364,-0.04122425615787506,0.5277084708213806,0.05143461668704033,0.009867277376334279,-0.008325888533430841

+24.9832855,-0.015230013988912106,-0.0442621074616909,0.5279596447944641,0.05335661377922794,0.00891241234516814,-0.006522647324595278

+24.9920695,-0.014726472087204456,-0.0409732311964035,0.52449631690979,0.05267027715431307,0.009334678057979388,-0.007879373066666997

+25.0028104,-0.015440290793776512,-0.04418569803237915,0.5216711759567261,0.05420180667698986,0.008143981959217311,-0.0065478515486442216

+25.0115934,-0.014881766401231289,-0.040921278297901154,0.518081545829773,0.05362334134595718,0.008407709224657615,-0.007894081127393277

+25.0223288,-0.015589505434036255,-0.04414854198694229,0.5151536464691162,0.055295901076468194,0.007145064355777439,-0.0060194690914302275

+25.0320856,-0.015012956224381924,-0.04083580896258354,0.5114918947219849,0.05467853106979314,0.00695900761377544,-0.007098377990218592

+25.0418505,-0.015760060399770737,-0.04403684660792351,0.5084038376808167,0.05634938657030217,0.00553468682441367,-0.005082197250104842

+25.0516106,-0.015155443921685219,-0.04067860543727875,0.5046656131744385,0.055738272507739495,0.005692422897906843,-0.0059036583206235485

+25.0623464,-0.015872953459620476,-0.04391229525208473,0.5015410780906677,0.05727352226494603,0.0042007269749407454,-0.0034052155022509536

+25.0711256,-0.015274615958333015,-0.040528785437345505,0.497768372297287,0.05681869021480143,0.004158863657111229,-0.004001651950938581

+25.0818616,-0.01601455546915531,-0.04369295760989189,0.4945027828216553,0.05873648620921224,0.0026239986794415328,-0.0015061690504779598

+25.0916217,-0.015431790612637997,-0.04031652584671974,0.4907159209251404,0.058552938949304426,0.0025861684443673214,-0.0019000533394305792

+25.1023625,-0.01615598239004612,-0.043504498898983,0.48742470145225525,0.06012488784042077,0.0014447711548259883,0.0005490290647660013

+25.1121681,-0.015582555904984474,-0.04020141065120697,0.48359179496765137,0.05984810701775916,0.0018322881187480926,-0.0002141002689584138

+25.1228548,-0.016346246004104614,-0.04333261772990227,0.4801693558692932,0.061278257021780226,0.0008611619873355918,0.0021401519933950293

+25.130666,-0.01576903834939003,-0.04000968486070633,0.4762854278087616,0.06065437995045361,0.0015807406057242424,0.0014878951123887415

+25.1423779,-0.016563160344958305,-0.04306044057011604,0.4727114140987396,0.061963246139969654,0.0006959281328031099,0.003915200061714961

+25.1521731,-0.0160501878708601,-0.03985771909356117,0.46882396936416626,0.06131545288024347,0.0013800320978326881,0.0034458313172471343

+25.1619049,-0.016852786764502525,-0.04282836988568306,0.4651457369327545,0.0626536704023068,0.0004166949222295022,0.005831949800312986

+25.1716603,-0.016293847933411598,-0.03965452313423157,0.4611061215400696,0.06187111452343936,0.0008883715164891031,0.005165192744409893

+25.1824231,-0.01713009923696518,-0.04260994493961334,0.4572996497154236,0.06328600997844658,-0.0004312264464333971,0.007213352230683391

+25.1912342,-0.016572387889027596,-0.03941500559449196,0.45319482684135437,0.06280464736687848,-0.0005128586616131998,0.0061063239778697135

+25.2019456,-0.017365291714668274,-0.04240448772907257,0.4494057297706604,0.06440813726626714,-0.0019841411117820064,0.007978487239180605

+25.2127158,-0.016821159049868584,-0.03923279047012329,0.4452645182609558,0.06377318807272032,-0.0020155743854189294,0.006940175888561553

+25.2224381,-0.016961202025413513,-0.039238035678863525,0.4374319314956665,0.06411056612972357,-0.002573266741651801,0.007406103381869928

+25.2322062,-0.016596470028162003,-0.038046251982450485,0.437192440032959,0.06319848827689534,-0.0021209087829188733,0.006891023748877024

+25.2419498,-0.01668027974665165,-0.0379297249019146,0.42926397919654846,0.06355200768925891,-0.0019901014011482854,0.0072224346680880395

+25.2516905,-0.016554497182369232,-0.03749927133321762,0.4250776469707489,0.06274935324048239,-0.0015508557409023398,0.007127710263746296

+25.2614495,-0.016583019867539406,-0.0374288409948349,0.42104944586753845,0.06312301314877213,-0.0012124619728674244,0.0074613637210658645

+25.2721872,-0.016568439081311226,-0.03732772916555405,0.4169425666332245,0.06265724997140679,-0.0006226634829570092,0.007942147994282445

+25.2819414,-0.016593147069215775,-0.037268634885549545,0.41288453340530396,0.06303816619763528,-0.00026161277213210786,0.008706057909858112

+25.2917799,-0.01661854051053524,-0.03736855089664459,0.4087958037853241,0.062481441686271934,-0.00023557804649401205,0.00992261224534858

+25.3015404,-0.01664615422487259,-0.03733132407069206,0.4087958037853241,0.06289236816354815,-0.00043158106048793503,0.01114922026585438

+25.3122736,-0.016728127375245094,-0.03745965659618378,0.40466630458831787,0.0623795282859415,-0.0007771006526207854,0.012732749526579282

+25.3220287,-0.016761302947998047,-0.037466149777173996,0.4005618095397949,0.06269584597848475,-0.0011293372906248113,0.013784722732598797

+25.331789,-0.0168496984988451,-0.03761359304189682,0.3964208662509918,0.06217596482813956,-0.0014841771523743527,0.014717835756461026

+25.3415897,-0.016888992860913277,-0.03766462206840515,0.3922812342643738,0.06248210009796362,-0.0017899912833987263,0.015044619460487107

+25.351313,-0.017014898359775543,-0.03787998855113983,0.3881464898586273,0.062149722639764315,-0.0022190317241364797,0.015386990620750777

+25.3630215,-0.01706424355506897,-0.03798037767410278,0.38398227095603943,0.062414129608381504,-0.002495999359498978,0.015279046015629136

+25.3708315,-0.01721101440489292,-0.03825073689222336,0.37983769178390503,0.06210329955789046,-0.0028819186206234257,0.01571184128661337

+25.3815692,-0.017272310331463814,-0.03840100020170212,0.3756641149520874,0.06232759013680908,-0.0027846842381044666,0.01619812444502138

+25.3903492,-0.01742001250386238,-0.03869177773594856,0.3715305030345917,0.062148771167108784,-0.002892643835588069,0.017083314607625764

+25.4020615,-0.017492754384875298,-0.038888707756996155,0.367338091135025,0.062434857574585306,-0.0025654268358766973,0.01794031463282015

+25.4118251,-0.017657676711678505,-0.03923055902123451,0.36317408084869385,0.06195209224979889,-0.0022822121736778057,0.018503561829757834

+25.4225566,-0.017741713672876358,-0.03947647288441658,0.3589441180229187,0.062062297866164746,-0.0017990163583583587,0.018774211654918445

+25.4323211,-0.01792987808585167,-0.03986252844333649,0.35478806495666504,0.061309902818368935,-0.0014403851071410213,0.018702100347165605

+25.4420903,-0.018024824559688568,-0.04015864059329033,0.35055792331695557,0.06128916188099495,-0.000901804149485694,0.017820771911322704

+25.451841,-0.0181900542229414,-0.04057200998067856,0.3463558256626129,0.06072955407112384,-0.0010305103788796656,0.01671687264105518

+25.460625,-0.01829173043370247,-0.040913332253694534,0.342114120721817,0.06071560741229549,-0.0006118102413371837,0.015404775883545446

+25.4713576,-0.018436411395668983,-0.04129636287689209,0.3379369378089905,0.060262776898103144,-0.00034492850998402895,0.01426325916487249

+25.482097,-0.01854163222014904,-0.04167093336582184,0.3336975872516632,0.060033340876466466,0.00010877895628590639,0.013418894106685402

+25.4918571,-0.018638016656041145,-0.04213513806462288,0.32946375012397766,0.059294420463265496,0.0005232451718114692,0.0132605924229746

+25.5016172,-0.01874280720949173,-0.04254268854856491,0.32522648572921753,0.0589579460399067,0.001137159990857055,0.013409576552770204

+25.5113774,-0.01885613240301609,-0.043003324419260025,0.32103726267814636,0.05807298168398366,0.001489862371779759,0.013660827103307353

+25.5221089,-0.018959330394864082,-0.04344092309474945,0.31683117151260376,0.05741572331570757,0.001757586528735444,0.013662481490082094

+25.5318686,-0.01903911679983139,-0.04394533112645149,0.31265705823898315,0.05609731661762624,0.0021607418126290984,0.013420557351473045

+25.5426133,-0.019137855619192123,-0.04441319406032562,0.30845457315444946,0.05521736382874396,0.0029773385291208894,0.012965668482942982

+25.5523648,-0.019293300807476044,-0.04492950811982155,0.30391743779182434,0.05369517611660809,0.0035441384363188643,0.012226315426505254

+25.5621295,-0.02360273338854313,-0.044766198843717575,0.2972806692123413,0.054655957039641226,0.0014290235319604106,0.012643219510868267

+25.5718943,-0.02374553121626377,-0.044266894459724426,0.2929422855377197,0.052920176884796395,0.0028549594710793845,0.010996621796713135

+25.5816451,-0.02469281665980816,-0.046929266303777695,0.28843623399734497,0.0534831817717563,0.0033597832984966895,0.010889366692247706

+25.5904332,-0.024657636880874634,-0.04531253129243851,0.28411629796028137,0.05167886181515291,0.0053749786467984255,0.009389961254119113

+25.602145,-0.024946924299001694,-0.04588059335947037,0.2799086570739746,0.05032888713380005,0.006957967954921414,0.00853223518541392

+25.6119009,-0.024976637214422226,-0.045510899275541306,0.27555596828460693,0.048014081948573574,0.009095094719685842,0.00729251661846038

+25.6216608,-0.02601434662938118,-0.048429787158966064,0.2711196839809418,0.04840081358605101,0.010189512975321599,0.006975980011361834

+25.6311098,-0.025868259370326996,-0.04691833630204201,0.26687195897102356,0.04614145659678023,0.012069192743011613,0.0059329951774929925

+25.6418454,-0.026133814826607704,-0.04750167578458786,0.26268935203552246,0.04452423846016395,0.013573581396064313,0.005310375197580716

+25.6518451,-0.026097284629940987,-0.047259826213121414,0.2583138644695282,0.042137217024053784,0.015231560453757387,0.004584945465670306

+25.6615831,-0.027058664709329605,-0.05012740194797516,0.2539554536342621,0.04223822828883894,0.015572481613135227,0.004811569109051918

+25.6703796,-0.026812463998794556,-0.04871397837996483,0.24965660274028778,0.03976157152502629,0.016776996460110372,0.0036256390079775795

+25.6820791,-0.027755483984947205,-0.05123415216803551,0.24532777070999146,0.03944587944760967,0.016949903863190906,0.0032071310443328744

+25.691834,-0.027350885793566704,-0.04962727427482605,0.24094080924987793,0.03685040958590677,0.01795651922896256,0.0013284736459783166

+25.7016273,-0.028184985741972923,-0.05198957398533821,0.23667418956756592,0.0365322480105686,0.01805760224593123,0.0005299132127807603

+25.7103977,-0.027720343321561813,-0.05047982186079025,0.2322455197572708,0.03379825492731371,0.019085052033980324,-0.001662627148833738

+25.7220953,-0.027872934937477112,-0.051059845834970474,0.22806327044963837,0.03184282348512808,0.019517089053787774,-0.0029158983923678614

+25.7308756,-0.027673229575157166,-0.05074991658329964,0.22368064522743225,0.029254055246691654,0.02041784844915942,-0.004360184255392976

+25.7406391,-0.028409261256456375,-0.05341281369328499,0.2194356471300125,0.028621703449323084,0.02034000048296602,-0.004334113520391418

+25.7513708,-0.027943775057792664,-0.05215673893690109,0.21504130959510803,0.026168793028439812,0.020634292322228683,-0.005746314095927365

+25.7611305,-0.028625687584280968,-0.05446846783161163,0.2108374387025833,0.025617127182718708,0.020154167531350537,-0.00574632069679007

+25.7718684,-0.028124066069722176,-0.053011659532785416,0.20652048289775848,0.023041101370987988,0.0205133933566855,-0.006765700497365549

+25.7816264,-0.028760969638824463,-0.05525350570678711,0.20231890678405762,0.022361982987166157,0.01994795434608972,-0.0063928487912927705

+25.7923635,-0.028134813532233238,-0.053762707859277725,0.19790427386760712,0.019706081847410708,0.020003615035632076,-0.007694863762817798

+25.8021474,-0.028639525175094604,-0.05600708723068237,0.19383621215820312,0.018717198958718304,0.01943610657833592,-0.007736771663225163

+25.8109307,-0.028009608387947083,-0.05456165969371796,0.1894911676645279,0.01588601312053172,0.01934606088997777,-0.00946073528786127

+25.8226198,-0.028502266854047775,-0.056721802800893784,0.18541015684604645,0.015108430871887697,0.018637493425110115,-0.009642825906180267

+25.8304262,-0.027848822996020317,-0.055235669016838074,0.1811336725950241,0.01247246467145865,0.01860763472322218,-0.010928813704871202

+25.8409556,-0.0282515250146389,-0.05735194310545921,0.17715275287628174,0.011783899218602359,0.017970438263110698,-0.01021294298843016

+25.851692,-0.027549415826797485,-0.05587811768054962,0.17295151948928833,0.009186014853325323,0.01791955411958204,-0.010981773815297457

+25.8605013,-0.027956554666161537,-0.05794987827539444,0.16905340552330017,0.008405820539853906,0.017025697737914094,-0.01019618362664498

+25.8712125,-0.027220893651247025,-0.05652611702680588,0.16499121487140656,0.005839887792004572,0.0171462202135647,-0.01063992433025413

+25.8819484,-0.027612602338194847,-0.058427706360816956,0.161124587059021,0.005050259305254275,0.016716954859500973,-0.00987479178966518

+25.890732,-0.026844723150134087,-0.05713175982236862,0.15711209177970886,0.002656213421878662,0.01688003779651319,-0.010764814826933264

+25.9014686,-0.02717735804617405,-0.058929577469825745,0.15331830084323883,0.0022425055203307695,0.01614550441617558,-0.010599843589652483

+25.9102523,-0.026337334886193275,-0.05758160725235939,0.14935290813446045,0.00021214998813454857,0.01622131388707395,-0.011874361294656815

+25.9219913,-0.026602569967508316,-0.05935867130756378,0.14568160474300385,-0.0002487158437027061,0.015377497284706266,-0.011815765617290306

+25.9317503,-0.025709768757224083,-0.05805652216076851,0.14178535342216492,-0.002447156573551576,0.015032423801932737,-0.013074475408918923

+25.9405102,-0.02598693035542965,-0.0597306527197361,0.13814139366149902,-0.0028162038381601365,0.01424657109522586,-0.012769617181845175

+25.951245,-0.02507433481514454,-0.05846455693244934,0.1343306601047516,-0.005162431251673628,0.01393821669533596,-0.013951931023111461

+25.9610036,-0.025308599695563316,-0.060079142451286316,0.130743145942688,-0.0056572174611785415,0.012726062601174964,-0.01394102035035512

+25.9717404,-0.02436365932226181,-0.05879117175936699,0.12699459493160248,-0.007427906044800497,0.0122140196287148,-0.01513986051562619

+25.9815039,-0.024571089074015617,-0.06035583093762398,0.12348181009292603,-0.008015604514151073,0.010923315155345663,-0.014972018483735337

+25.9912611,-0.02363067865371704,-0.05909325182437897,0.11983679980039597,-0.009866196793620063,0.010245914573123632,-0.015655894757529404

+26.0000441,-0.023820841684937477,-0.06055686995387077,0.11636163294315338,-0.01015285518841821,0.008595982095392073,-0.014951407846624132

+26.0107814,-0.022850926965475082,-0.05924023315310478,0.11277005076408386,-0.011829674087575733,0.007632701687931002,-0.01483019078693835

+26.0215186,-0.022994207218289375,-0.06067786365747452,0.10936865955591202,-0.012208326735110216,0.005547179009009558,-0.013286798952354144

+26.0312806,-0.02203821763396263,-0.059378381818532944,0.1058536246418953,-0.013902202115055873,0.004528535517572618,-0.013132554386470228

+26.0420169,-0.02218010649085045,-0.06075580045580864,0.10250277072191238,-0.014137512412276676,0.0029834664565080485,-0.01194747734786915

+26.0517765,-0.021224308758974075,-0.059476979076862335,0.09906835108995438,-0.015940816078450395,0.0026509959415770197,-0.012033942096768942

+26.0615318,-0.0213320292532444,-0.06078626215457916,0.09580934047698975,-0.016230962173100265,0.0016597067378430553,-0.011092861515393676

+26.0712925,-0.020403534173965454,-0.05949370190501213,0.0924840196967125,-0.018024406836082918,0.0014150094720254212,-0.011353449960516961

+26.0820326,-0.020499177277088165,-0.06071802228689194,0.08929493278265,-0.018416112277231358,0.0006063336874589525,-0.010360619523194448

+26.0908166,-0.01959238573908806,-0.059476111084222794,0.08607037365436554,-0.020219955748435114,0.0005631546517826813,-0.010402231701564221

+26.1015526,-0.019621023908257484,-0.06058257445693016,0.0830027237534523,-0.020411785911839467,0.00026920788558243923,-0.009035786067495758

+26.1113092,-0.018703723326325417,-0.0594019778072834,0.07984162122011185,-0.021928198795797514,0.0004963620437309994,-0.008623665383307628

+26.1210679,-0.018794748932123184,-0.060482852160930634,0.07680373638868332,-0.021998728293661812,5.504207459398065e-05,-0.007167526396694345

+26.1318087,-0.017961962148547173,-0.05922367796301842,0.07385894656181335,-0.02385460819859504,0.000332115645509818,-0.006949784670668431

+26.1405886,-0.01798359677195549,-0.06027493253350258,0.07100583612918854,-0.024009149762949215,-0.00047346626941839436,-0.005846558407447436

+26.151386,-0.0175817608833313,-0.060279469937086105,0.06821750849485397,-0.024601265063336483,-0.00146241124377789,-0.0054899915280820916

+26.1601079,-0.01736011542379856,-0.06049736589193344,0.06534004956483841,-0.02445578579589852,-0.002681924785035897,-0.005025084409401311

+26.1708451,-0.01697455532848835,-0.06050676479935646,0.06263309717178345,-0.025155820012435503,-0.0037393724445861135,-0.00512753850314494

+26.181631,-0.01662438176572323,-0.06049640104174614,0.059948403388261795,-0.025233686130676176,-0.004434010100904575,-0.005190490189866546

+26.1904263,-0.01624932885169983,-0.060493435710668564,0.05739954859018326,-0.02626664696453949,-0.004849231176358195,-0.004992131811940178

+26.2020797,-0.015866165980696678,-0.0603007897734642,0.05480259284377098,-0.026486477373797675,-0.004869534180504513,-0.004648179260324929

+26.2109201,-0.015497488901019096,-0.06026491895318031,0.05240006372332573,-0.027550905074645336,-0.004949275345454705,-0.0036735761255449117

+26.2225729,-0.015074152499437332,-0.06005440279841423,0.050005752593278885,-0.02796475247729013,-0.0045606980918408485,-0.0028990814172224176

+26.2313574,-0.014707253314554691,-0.05998608469963074,0.04772664234042168,-0.029057557573222547,-0.00389230020839194,-0.0014658474483565504

+26.2412043,-0.014314639382064342,-0.05978225916624069,0.04538390412926674,-0.02920878334013552,-0.0032159434494593653,0.0003004628785719299

+26.2509998,-0.013952243141829967,-0.059691883623600006,0.0432264469563961,-0.030068386005325735,-0.002796082823041713,0.002436484579125097

+26.2607504,-0.013532118871808052,-0.05948355048894882,0.04112052172422409,-0.03032441725003886,-0.0023881555211091856,0.003640515493101812

+26.2714597,-0.013169374316930771,-0.05938160791993141,0.039157986640930176,-0.03111135629271345,-0.002871415569142853,0.004168133104823607

+26.2812811,-0.012747393921017647,-0.05917263776063919,0.037262171506881714,-0.031506973156483126,-0.00447346611314023,0.003526637682316928

+26.2920184,-0.012386048212647438,-0.05906461924314499,0.03554423153400421,-0.03232990146880242,-0.0074190638960702675,0.0021883803465909918

+26.3007399,-0.01200968399643898,-0.05886663496494293,0.03388576954603195,-0.032862669140916484,-0.011250406279378468,0.00041645437812131065

+26.3105045,-0.011664562858641148,-0.05875110998749733,0.03242732957005501,-0.033816620155733224,-0.01449259288818579,-0.001441524147264822

+26.3212365,-0.01133350282907486,-0.05863438546657562,0.031060317531228065,-0.03470023589094758,-0.017482677391284472,-0.0028819118165767364

+26.3300196,-0.011019871570169926,-0.05851457640528679,0.02979053556919098,-0.03537185055850159,-0.020484288528799615,-0.002841405628710806

+26.3397844,-0.010727118700742722,-0.05839090421795845,0.02862950786948204,-0.03608608715519356,-0.022889529890406882,-0.001217223962431158

+26.3513337,-0.009738571010529995,-0.057400207966566086,0.02733670361340046,-0.03757404241324384,-0.024408074837419504,0.0011095381379897793

+26.3610899,-0.009437913075089455,-0.05719093978404999,0.026347681879997253,-0.03814590107614907,-0.025650644181309787,0.006012373806305485

+26.3708488,-0.008937575854361057,-0.05688491463661194,0.025254106149077415,-0.039270709362103993,-0.025593659377500542,0.010976916522160854

+26.3815855,-0.008675757795572281,-0.056681107729673386,0.024399537593126297,-0.03943279347668166,-0.025395757649566794,0.014526374384927437

+26.3913489,-0.008328493684530258,-0.05664575845003128,0.023471469059586525,-0.04026491658045368,-0.025019922982753972,0.016028363910646073

+26.4148172,-0.008113231509923935,-0.056476105004549026,0.022738317027688026,-0.04108536065393426,-0.02419162542330816,0.01181418616730416

+26.4225783,-0.007838648743927479,-0.056512005627155304,0.02190621756017208,-0.04108536065393426,-0.02419162542330816,0.01181418616730416

+26.4753178,-0.007669062353670597,-0.05637969821691513,0.02129048854112625,-0.04114547483808176,-0.023611591117867373,0.0060886939916466425

+26.5045982,-0.0074873329140245914,-0.0564098060131073,0.020596209913492203,-0.042186336056808896,-0.0228261441646518,-0.0004743283552244232

+26.5397678,-0.007363005541265011,-0.05629724636673927,0.020071610808372498,-0.043323767040411576,-0.022874305629789107,-0.008105045499158633

+26.563158,-0.007259103935211897,-0.05630992352962494,0.019460681825876236,-0.043323767040411576,-0.022874305629789107,-0.008105045499158633

+26.6100402,-0.007179696578532457,-0.05619705095887184,0.018996749073266983,-0.04357708589394442,-0.022192079414065466,-0.003744282567870034

+26.6509986,-0.007116999011486769,-0.05618910863995552,0.018418893218040466,-0.04324272826560671,-0.020542735697004055,-0.0004879108641216524

+26.7037023,-0.00708182156085968,-0.05607445910573006,0.01804155856370926,-0.04352304866663151,-0.01824204110870517,0.0016774870658587623

+26.7394268,-0.007090019062161446,-0.056098148226737976,0.017490457743406296,-0.04352304866663151,-0.01824204110870517,0.0016774870658587623

+26.7755407,-0.007098598871380091,-0.055999476462602615,0.017160870134830475,-0.04322058416602924,-0.01568274515747693,0.0017823887320310152

+26.8455418,-0.007118286099284887,-0.056032273918390274,0.01662440039217472,-0.043193988294244916,-0.010210730375156348,-0.0025063447211723412

+26.8859134,-0.007155337370932102,-0.055951353162527084,0.016253378242254257,-0.043432526382649765,-0.008080054842140796,-0.005824454778120468

+26.9161677,-0.007146681193262339,-0.055949535220861435,0.015672070905566216,-0.04275509998120521,-0.006737746364178009,-0.009022208667044049

+26.9572149,-0.007138298824429512,-0.05579051375389099,0.014687374234199524,-0.04250988887647057,-0.005548485439778889,-0.0117543929559112

+27.0040632,-0.007138298824429512,-0.05579051375389099,0.014687374234199524,-0.04122235543891272,-0.0040396587991758425,-0.013321013850283727

+27.0567666,-0.0068265399895608425,-0.05593472719192505,0.014024999924004078,-0.04094162437505137,-0.0024166145083048805,-0.014696804106825926

+27.1211869,-0.0068265399895608425,-0.05593472719192505,0.014024999924004078,-0.03958749615841198,-0.0017142198998247801,-0.014267043361946695

+27.1563188,-0.00671179685741663,-0.05583929643034935,0.013214999809861183,-0.03958749615841198,-0.0017142198998247801,-0.014267043361946695

+27.1914543,-0.00671179685741663,-0.05583929643034935,0.013214999809861183,-0.03936038065310109,-0.0019464482849630314,-0.011780510915042808

+27.2558704,-0.006687600631266832,-0.05566747859120369,0.012660462409257889,-0.037825492437460646,-0.006371768570212897,-0.005550087415622792

+27.291058,-0.006687600631266832,-0.05566747859120369,0.012660462409257889,-0.037825492437460646,-0.006371768570212897,-0.005550087415622792

+27.3612783,-0.0068245236761868,-0.056060608476400375,0.012481584213674068,-0.036706028207142784,-0.008667236892340321,-0.0033967177668489993

+27.3905918,-0.006664075888693333,-0.055423587560653687,0.012131273746490479,-0.036706028207142784,-0.008667236892340321,-0.0033967177668489993

diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/measured_flight_path.mat b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/measured_flight_path.mat
new file mode 100644
index 0000000000000000000000000000000000000000..a491e85f07463076931d6a3f8faaacf251cf6d9f
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/measured_flight_path.mat differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/pid_ctrl.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/pid_ctrl.m
new file mode 100644
index 0000000000000000000000000000000000000000..d2d02f45072c7c33c9b0f0af0f3f5a155234093d
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/pid_ctrl.m
@@ -0,0 +1,22 @@
+function [cmd, error_sum, error_prev] = pid_ctrl(setpoint,state, Kp, Ki, Kd, goal_error_sum, goal_error_prev)
+% Name: pid_ctrl
+% Authour: Phillip Jones (07/20/2022)
+% Description: Compute a PID control law
+% PID correction cmd = Kp*error + Ki*error_sum + Kd*error_diff
+%
+
+coder.extrinsic('evalin', 'assignin')
+
+% Compute PID error terms
+goal_error = setpoint - state;  % Current error
+goal_error_sum = goal_error_sum + goal_error; % Error sum
+goal_error_diff = goal_error - goal_error_prev; % Error difference
+
+% Compute PID correction command
+pid_cmd = Kp*goal_error + Ki*goal_error_sum + Kd*goal_error_diff;
+
+% Return results
+cmd = pid_cmd;
+error_sum = goal_error_sum;  % Use as input on next pid function call
+error_prev = goal_error;     % Use as input on next pid function call 
+end
\ No newline at end of file
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_example.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_example.m
new file mode 100644
index 0000000000000000000000000000000000000000..8413ed2ef4ac4050395e6420b66b5acde177e688
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_example.m
@@ -0,0 +1,186 @@
+% Plot Quadcopter motion
+
+% Constants
+g = 9.8;      % (m/s^2) Gravity
+m = 28/1000;  % (Kg) Mass of quad (Crazy Fly flying weight (Foster-2015)
+F_hover = m*g; % Force required for Crazy Flie to hover
+
+% Initial states
+x1  = 0;  % x
+x2  = 0;  % y
+x3  = 0;  % z
+x4  = 0;  % phi
+x5  = 0;  % theta
+x6  = 0;  % psi
+x7  = 0;  % x_dot
+x8  = 0;  % y_dot
+x9  = 0;  % z_dot
+x10 = 0;  % phi_dot
+x11 = 0;  % theta_dot
+x12 = 0;  % psi_dot
+
+X_init=[x1  x2  x3  x4  x5  x6 ... 
+        x7  x8  x9  x10 x11 x12];
+
+% Initialize forces
+u1 = F_hover;  % Total force (Note: always normal to yaw motion)
+u2 = 0;   % Roll force
+u3 = 0;   % Pitch force
+u4 = 0;   % Yaw force
+U = [u1 u2 u3 u4];    
+
+% Simulation time
+tstep = .001; % Time step in seconds
+tspan=[0 tstep]; 
+
+% Initilze loop body varibles
+
+% Setpoint (i.e refernce)
+alt_setpoint = 1;  % Altitude (-Z axis position) 
+y_setpoint = 1;  % Y axis position
+x_setpoint = 1;  % X axis position
+
+% X_ref : Set point refernce state for quad to go to
+%         In this case for initial state, to X/Y/Z setpoint
+%         with 0 velocities, and level
+X_ref = [x_setpoint y_setpoint -alt_setpoint 0 0 0 ...
+         0 0 0 0 0 0];
+
+
+% Simulate model for 1st timestep (tstep)
+% PHJ: error bound setting, options = odeset('AbsTol',1e-9,'RelTol',1e-9);
+[t, X] = ode113(@(t,X) compute_quad(t,X,U), tspan, X_init); % Simulate
+Xplot = [t, X]; % log time and state for plotting later
+U_plot = [tspan(1), U];
+
+% Simulate for discrete intervals for n more time steps
+n = 20000;  
+for i=1:(n-1)
+  [t, y, X, U, tspan] = compute_quad_wrapper(t, tstep, X, U, X_ref,F_hover, tspan);
+
+% Log control forces
+%U_plot = [U_plot; [tspan(1), U]];
+
+end
+
+
+% Reuse t and X for ploting
+t = Xplot(:,1); 
+X = Xplot(:,2:13);
+
+td = U_plot(:,1);
+U  = U_plot(:,2:5);
+
+% Convert from radians to degrees
+X(:,4) = X(:,4)*(180/pi);  % phi
+X(:,5) = X(:,5)*(180/pi);  % theta
+X(:,6) = X(:,6)*(180/pi);  % psi
+X(:,10) = X(:,10)*(180/pi);  % phi_dot
+X(:,11) = X(:,11)*(180/pi);  % theta_dot
+X(:,12) = X(:,12)*(180/pi);  % psi_dot
+
+[t, X]; % Print state over entire simulation time.
+
+% Plot results of simulation
+% https://en.wikipedia.org/wiki/List_of_Unicode_characters
+plot_fontsize = 12;
+plot_linewidth = 1;
+plot_rows = 3;
+plot_cols = 6;
+
+subplot(plot_rows,plot_cols,1)
+plot(t,X(:,1), 'green', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('X (m)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,2)
+plot(t,X(:,2), 'blue', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('Y (m)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,3)
+plot(t,-X(:,3), 'Color', '#D95319', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('Z (m)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,4)
+plot(t,X(:,4), 'magenta', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel(['\phi (' char(176) ')'])
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,5)
+plot(t,X(:,5), 'cyan', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel(['\theta (' char(176) ')'])
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,6)
+plot(t,X(:,6), 'black', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel(['\psi (' char(176) ')'])
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,7)
+plot(t,X(:,7), 'green', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('X^\prime (m/s)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,8)
+plot(t,X(:,8), 'blue', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('Y^\prime (m/s)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,9)
+plot(t,-X(:,9), 'Color', '#D95319', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('Z^\prime (m/s)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,10)
+plot(t,X(:,10), 'magenta', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel(['\phi^\prime (' char(176) '/s)'])
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,11)
+plot(t,X(:,11), 'cyan', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel(['\theta^\prime (' char(176) '/s)'])
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,12)
+plot(t,X(:,12), 'black', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel(['\psi^\prime (' char(176) '/s)'])
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,13)
+plot(td,U(:,1), 'Color', '#D95319', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('Thrust (N)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,14)
+plot(td,U(:,2), 'magenta', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('\phi Force (N)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,15)
+plot(td,U(:,3), 'cyan', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('\theta Force (N)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
+subplot(plot_rows,plot_cols,16)
+plot(td,U(:,4), 'black', 'linewidth', plot_linewidth)
+grid; xlabel('t (s)'); ylabel('\psi Force (N)')
+set(gca,'FontSize',plot_fontsize)
+title('Title: ')
+
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_example_with_wrapper.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_example_with_wrapper.m
new file mode 100644
index 0000000000000000000000000000000000000000..1815aa2c323c689fd8e98a3c160ce3b8e6ce08d4
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_example_with_wrapper.m
@@ -0,0 +1,108 @@
+% Plot Quadcopter motion
+
+% Constants
+g = 9.8;      % (m/s^2) Gravity
+m = 28/1000;  % (Kg) Mass of quad (Crazy Fly flying weight (Foster-2015)
+F_hover = m*g; % Force required for Crazy Flie to hover
+%gamepad = vrjoystick(1);
+
+% Initial states
+x1  = 0;  % x
+x2  = 0;  % y
+x3  = 0;  % z
+x4  = 0;  % phi
+x5  = 0;  % theta
+x6  = 0;  % psi
+x7  = 0;  % x_dot
+x8  = 0;  % y_dot
+x9  = 0;  % z_dot
+x10 = 0;  % phi_dot
+x11 = 0;  % theta_dot
+x12 = 0;  % psi_dot
+
+X_init=[x1  x2  x3  x4  x5  x6 ... 
+        x7  x8  x9  x10 x11 x12];
+
+% Initialize forces
+u1 = F_hover;  % Total force (Note: always normal to yaw motion)
+u2 = 0;   % Roll force
+u3 = 0;   % Pitch force
+u4 = 0;   % Yaw force
+U = [u1 u2 u3 u4];    
+
+% Simulation time
+tstep = .001; % Time step in seconds
+tspan=[0 tstep]; 
+runtime=15;
+
+% Initilze loop body varibles
+
+% Setpoint (i.e refernce)
+alt_setpoint = 3;  % Altitude (-Z axis position) 
+y_setpoint = 1;  % Y axis position
+x_setpoint = 1;  % X axis position
+
+% X_ref : Set point refernce state for quad to go to
+%         In this case for initial state, to X/Y/Z setpoint
+%         with 0 velocities, and level
+X_ref = [x_setpoint y_setpoint -alt_setpoint 0 0 0 ...
+         0 0 0 0 0 0];
+
+ylogs = zeros(15000,7);
+
+
+% % Simulate model for 1st timestep (tstep)
+% % PHJ: error bound setting, options = odeset('AbsTol',1e-9,'RelTol',1e-9);
+[t, X] = ode45(@(t,X) compute_quad(t,X,U), tspan, X_init); % Simulate
+ Xplot = [t, X]; % log time and state for plotting later
+ U_plot = [tspan(1), U];
+ 
+ time = 0;
+ 
+ for i = 1:15000
+     % setpoint = drone_gamepad_input(X_ref(4), X_ref(3), X_ref(1), X_ref(2), gamepad);
+     % X_ref(1) = setpoint(3);
+     % X_ref(2) = setpoint(4);
+     % X_ref(3) = setpoint(1);
+     % X_ref(4) = setpoint(2);
+     
+     if i == 2500
+         alt_setpoint = 5;  % Altitude (-Z axis position) 
+         y_setpoint = 0;  % Y axis position
+         x_setpoint = 0;  % X axis position
+         X_ref = [x_setpoint y_setpoint -alt_setpoint 0 0 0 ...
+              0 0 0 0 0 0];
+     end
+ 
+     if i == 5000
+         alt_setpoint = 0;  % Altitude (-Z axis position) 
+         y_setpoint = 0;  % Y axis position
+         x_setpoint = 0;  % X axis position
+         X_ref = [x_setpoint y_setpoint -alt_setpoint 0 0 0 ...
+              0 0 0 0 0 0];
+     end
+ 
+     if i == 7500
+         alt_setpoint = 8;  % Altitude (-Z axis position) 
+         y_setpoint = 0;  % Y axis position
+         x_setpoint = 0;  % X axis position
+         X_ref = [x_setpoint y_setpoint -alt_setpoint 0 0 0 ...
+              0 0 0 0 0 0];
+     end
+ 
+     if i > 10000 % not sure why this doesn't actually control the yaw, unless this treats yaw exactly the same as pitch and roll!!!
+         X_ref = [x_setpoint y_setpoint -alt_setpoint 0 0 1 ...
+              0 0 0 0 0 0];
+     end
+ 
+     [y, X, U, tspan] = compute_quad_wrapper(tstep, X, U, X_ref,F_hover, tspan);
+     time = time + tstep;
+ 
+     ylogs(i,1:7) = [time y];
+ 
+ end
+ 
+ % ylogs = ylogs.';
+ 
+ %save("logged_data","ylogs")
+ 
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_params.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_params.m
new file mode 100644
index 0000000000000000000000000000000000000000..3e1daecfd26a2510f5d6de884a19ba80e7c6d28e
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_params.m
@@ -0,0 +1,57 @@
+% Plot Quadcopter motion
+
+% Constants
+g = 9.8;      % (m/s^2) Gravity
+m = 23.1/1000;  % (Kg) Mass of quad (Crazy Fly flying weight (Foster-2015)
+F_hover = m*g; % Force required for Crazy Flie to hover
+%gamepad = vrjoystick(1);
+
+% Initial states
+x1  = 0;  % x
+x2  = 0;  % y
+x3  = 0;  % z
+x4  = 0;  % phi
+x5  = 0;  % theta
+x6  = 0;  % psi
+x7  = 0;  % x_dot
+x8  = 0;  % y_dot
+x9  = 0;  % z_dot
+x10 = 0;  % phi_dot
+x11 = 0;  % theta_dot
+x12 = 0;  % psi_dot
+
+X_init=[x1  x2  x3  x4  x5  x6 ... 
+        x7  x8  x9  x10 x11 x12];
+Xsize = 11;
+
+% Initialize forces
+u1 = F_hover;  % Total force (Note: always normal to yaw motion)
+u2 = 0;   % Roll force
+u3 = 0;   % Pitch force
+u4 = 0;   % Yaw force
+U = [u1 u2 u3 u4];    
+
+% Simulation time
+tstep = .001; % Time step in seconds
+tspan=[0 tstep]; 
+
+runtime=15;
+
+% Initilze loop body varibles
+
+% Setpoint (i.e refernce)
+alt_setpoint = 0;  % Altitude (-Z axis position) 
+y_setpoint = 0;  % Y axis position
+x_setpoint = 0;  % X axis position
+
+% X_ref : Set point refernce state for quad to go to
+%         In this case for initial state, to X/Y/Z setpoint
+%         with 0 velocities, and level
+X_ref = [x_setpoint y_setpoint -alt_setpoint 0 0 0 ...
+         0 0 0 0 0 0];
+
+% % Simulate model for 1st timestep (tstep)
+% % PHJ: error bound setting, options = odeset('AbsTol',1e-9,'RelTol',1e-9);
+[t, X] = ode45(@(t,X) compute_quad(t,X,U), tspan, X_init); % Simulate
+ Xplot = [t, X]; % log time and state for plotting later
+ U_plot = [tspan(1), U];
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_params_pid.m b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_params_pid.m
new file mode 100644
index 0000000000000000000000000000000000000000..ee94b5637a874e921a556f9663c02535d6fd9a26
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quad_params_pid.m
@@ -0,0 +1,97 @@
+% Plot Quadcopter motion
+
+% Constants
+g = 9.8;      % (m/s^2) Gravity
+m = 28/1000;  % (Kg) Mass of quad (Crazy Fly flying weight (Foster-2015)
+F_hover = m*g; % Force required for Crazy Flie to hover
+
+% Initial states
+x1  = 0;  % x
+x2  = 0;  % y
+x3  = 0;  % z
+x4  = 0;  % phi
+x5  = 0;  % theta
+x6  = 0;  % psi
+x7  = 0;  % x_dot
+x8  = 0;  % y_dot
+x9  = 0;  % z_dot
+x10 = 0;  % phi_dot
+x11 = 0;  % theta_dot
+x12 = 0;  % psi_dot
+
+X_init=[x1  x2  x3  x4  x5  x6 ... 
+        x7  x8  x9  x10 x11 x12];
+
+
+% Initialize forces
+u1 = F_hover;  % Total force (Note: always normal to yaw motion)
+u2 = 0;   % Roll force
+u3 = 0;   % Pitch force
+u4 = 0;   % Yaw force
+U = [u1 u2 u3 u4];   
+
+
+% Simulation time
+tstep = .001; % Time step
+tspan=[0 tstep]; 
+
+% Initilze loop body varibles
+
+% Altitude PID Control
+alt_setpoint = 0;  % Altitude (-Z axis)
+Kp_alt = 0.500;
+Ki_alt =  0.001;
+Kd_alt = 500;
+alt_error_sum = 0;    % Sum of error
+alt_error_prev = 0.;   % Previous error
+
+% Y position PID Controll (assuming 0 yaw, i.e., psi=0)
+y_setpoint = 0;  % Controlled by phi (roll) angle
+Kp_y = .105;
+Ki_y =  0;
+Kd_y = 140;
+y_error_sum = 0;    % Sum of error
+y_error_prev = 0;   % Previous error
+y_cmd = 0;          % correction force
+
+% phi (roll) angle PID Controll (assuming 0 yaw, i.e., psi=0)
+phi_setpoint = Kp_y*y_setpoint;  % phi  (Set by y_cmd)
+Kp_phi = .001;
+Ki_phi =  0;
+Kd_phi = 100;
+phi_error_sum = 0;    % Sum of error
+phi_error_prev = 0;   % Previous error
+phi_cmd = 0;          % correction force
+
+% X position PID Controll (assuming 0 yaw, i.e., psi=0)
+x_setpoint = 0;  % Controlled by -theta (-pitch) angle
+Kp_x = .105;
+Ki_x =  0;
+Kd_x = 140;
+x_error_sum = 0;    % Sum of error
+x_error_prev = 0;   % Previous error
+x_cmd = 0;          % correction force
+
+% theta (pitch) angle PID Controll (assuming 0 yaw, i.e., psi=0)
+theta_setpoint = -Kp_x*x_setpoint;  % theta  (Set by -x_cmd)
+Kp_theta = .001;
+Ki_theta =  0;
+Kd_theta = 100;
+theta_error_sum = 0;    % Sum of error
+theta_error_prev = 0;   % Previous error
+theta_cmd = 0;          % correction force
+
+% X_ref : Set points for quad to follow
+X_ref = [0 y_setpoint 0 0 0 0 ...
+         0 0 0 0 0 0];
+Xsize = 11;
+pid_states = [alt_error_sum alt_error_prev y_error_sum y_error_prev phi_error_sum phi_error_prev x_error_sum x_error_prev theta_error_sum theta_error_prev phi_setpoint theta_setpoint];
+pid_gains = [Kp_alt Ki_alt Kd_alt Kp_y Ki_y Kd_y Kp_phi Ki_phi Kd_phi Kp_x Ki_x Kd_x Kp_theta Ki_theta Kd_theta];
+
+ 
+
+% Simulate model for 1st timestep (tstep)
+% PHJ: error bound setting, options = odeset('AbsTol',1e-9,'RelTol',1e-9);
+[t, X] = ode45(@(t,X) compute_quad(t,X,U), tspan, X_init); % Sim
+Xplot = [t, X]; % log time and state for plotting later
+U_plot = [tspan(1), U];
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quadrotor_world_ucart.wrl b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quadrotor_world_ucart.wrl
new file mode 100644
index 0000000000000000000000000000000000000000..eb0ece0c87dd94275cc01905e42ff20b87bd800c
--- /dev/null
+++ b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/quadrotor_world_ucart.wrl
@@ -0,0 +1,1030 @@
+#VRML V2.0 utf8
+
+#Created with V-Realm Builder v2.0
+#Integrated Data Systems Inc.
+#www.ids-net.com
+
+
+PointLight {
+	location	-0.8 1 1
+}
+PointLight {
+	location	1.1 1.1 0
+}
+DEF Viewport_heli Viewpoint {
+	fieldOfView	0.785398
+	orientation	1 0 0  0.188496
+	position	0.024 -0.191 11.9975
+}
+DEF Helicopter Transform {
+	translation	0 0 0
+	scale	0.108 0.108 0.108
+	children [ 
+	    DEF Rotor_1 Transform {
+		    translation	10 0 10
+		    scale	1.00001 1.00001 1.00001
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    color	NULL
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+				    colorIndex	[  ]
+			    }
+
+		    }
+	    }
+
+	    DEF Rotor_2 Transform {
+		    translation	10 0 -10
+		    scale	0.999617 0.999617 0.999617
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+			    }
+
+		    }
+	    }
+
+	    DEF Rotor_3 Transform {
+		    translation	-10 0 -10
+		    scale	0.999617 0.999617 0.999617
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+			    }
+
+		    }
+	    }
+
+	    DEF Center Transform {
+		    translation	0 -1 0
+		    scale	1.11653 1.11653 1.11653
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+				    }
+
+			    }
+
+			    geometry	Box {
+				    size	5 1.5 5
+			    }
+
+		    }
+	    }
+
+	    DEF Rotor_4 Transform {
+		    translation	-10 0 10
+		    scale	0.999617 0.999617 0.999617
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    ambientIntensity	0.9551
+					    diffuseColor	0.6163 0.6163 0.6163
+					    shininess	0.3
+					    specularColor	0.3 0.3 0.3
+				    }
+
+			    }
+
+			    geometry	IndexedFaceSet {
+				    coord	DEF _v2%0 Coordinate {
+					    point	[ 1.87355 -2.12 -0.139033,
+							      0.783522 -2.076 0.446909,
+							      0.783515 -2.267 0.566909,
+							      0.783572 -2.266 -0.517091,
+							      1.87352 -2.12 0.566967,
+							      1.80752 -2.12 0.566963,
+							      1.87359 -2.266 -0.877033,
+							      1.87355 -2.267 -0.047033,
+							      1.87352 -2.267 0.566967,
+							      1.80752 -2.267 0.566963,
+							      1.80755 -2.12 -0.129037,
+							      1.80755 -2.267 -0.037037,
+							      1.80759 -2.266 -0.867037,
+							      1.80659 -2.12 -0.874037,
+							      1.87259 -2.12 -0.884034,
+							      -1.18645 -2.12 -0.139194,
+							      -1.18541 -2.12 -0.884194,
+							      -1.11941 -2.12 -0.874191,
+							      -1.12041 -2.266 -0.867191,
+							      -1.12045 -2.12 -0.129191,
+							      -1.12048 -2.12 0.566809,
+							      -1.12048 -2.267 0.566809,
+							      -1.18649 -2.267 0.566806,
+							      -1.18645 -2.267 -0.047194,
+							      -1.12045 -2.267 -0.037191,
+							      -1.18641 -2.266 -0.877194,
+							      -1.18649 -2.12 0.566806,
+							      -0.096428 -2.266 -0.517137,
+							      -0.096485 -2.267 0.566863,
+							      -0.096479 -2.076 0.446863,
+							      0.591406 -3.166 2.6379,
+							      0.095406 -3.166 2.63787,
+							      0.095406 -2.912 2.63787,
+							      0.219395 -3.166 2.85388,
+							      0.219395 -2.912 2.85388,
+							      0.467395 -2.912 2.85389,
+							      0.467395 -3.166 2.85389,
+							      0.467418 -2.912 2.42289,
+							      0.219418 -2.912 2.42288,
+							      0.591406 -2.912 2.6379,
+							      0.219418 -3.166 2.42288,
+							      0.467418 -3.166 2.42289,
+							      0.434395 -3.132 2.85389,
+							      0.252395 -3.132 2.85388,
+							      0.252395 -2.946 2.85388,
+							      0.434395 -2.946 2.85389,
+							      0.269336 -3.076 3.96788,
+							      0.417336 -3.129 3.96789,
+							      0.417336 -3.076 3.96789,
+							      0.269336 -3.129 3.96788,
+							      0.269395 -3.012 2.85388,
+							      0.269395 -3.066 2.85388,
+							      0.367395 -2.962 2.85389,
+							      0.319395 -2.962 2.85388,
+							      0.417395 -3.066 2.85389,
+							      0.417395 -3.012 2.85389,
+							      0.367336 -3.179 3.96789,
+							      0.319336 -3.179 3.96789,
+							      0.319395 -3.116 2.85388,
+							      0.367395 -3.116 2.85389,
+							      0.319336 -3.026 3.96789,
+							      0.367336 -3.026 3.96789,
+							      6.61556 0.193 -0.215784,
+							      5.14735 -0.086 3.80614,
+							      1.43223 -0.234 5.94594,
+							      -4.46066 -0.086 3.80563,
+							      -5.92844 0.192 -0.216444,
+							      -4.46123 0.471 -4.23737,
+							      -0.74512 0.619 -6.37717,
+							      3.47884 0.568 -5.63495,
+							      5.14777 0.471 -4.23786,
+							      5.14777 0.532 -4.23786,
+							      3.47884 0.628 -5.63495,
+							      -0.74512 0.68 -6.37717,
+							      -4.46123 0.531 -4.23737,
+							      -5.92844 0.253 -0.216444,
+							      -4.46066 -0.025 3.80563,
+							      1.43223 -0.173 5.94594,
+							      5.14735 -0.025 3.80614,
+							      6.61556 0.253 -0.215784,
+							      0.614972 0.679 -8.1101,
+							      0.614936 0.106 -7.4281,
+							      0.614936 -1.196 -7.4281,
+							      0.614972 -1.767 -8.1101,
+							      0.615018 -1.768 -9.0011,
+							      0.615054 -1.196 -9.6831,
+							      0.615062 -0.319 -9.8381,
+							      0.615054 0.106 -9.6831,
+							      0.615039 0.453 -9.3931,
+							      0.615018 0.679 -9.0011,
+							      0.530019 0.679 -9.0011,
+							      0.530039 0.453 -9.39311,
+							      0.530054 0.106 -9.68311,
+							      0.530062 -0.319 -9.83811,
+							      0.530054 -1.196 -9.68311,
+							      0.530019 -1.768 -9.0011,
+							      0.529972 -1.767 -8.1101,
+							      0.529936 -1.196 -7.4281,
+							      0.529928 -0.319 -7.2731,
+							      0.529936 0.106 -7.4281,
+							      0.529972 0.679 -8.1101,
+							      0.255231 -2.14915 -7.3791,
+							      0.758162 -2.59984 3.36791,
+							      0.594847 -2.54881 3.72511,
+							      -0.062854 -2.59984 3.36787,
+							      0.594839 -1.93645 3.87253,
+							      0.100415 -1.93645 3.8725,
+							      0.75818 -1.70965 3.02771,
+							      -0.062836 -1.70965 3.02767,
+							      0.758223 -1.02925 2.19989,
+							      -0.062793 -1.02925 2.19985,
+							      0.758299 -0.830803 0.75404,
+							      -0.062717 -0.830803 0.753997,
+							      0.758301 -0.314833 0.72002,
+							      -0.062715 -0.314833 0.719977,
+							      0.758416 -0.415926 -1.4647,
+							      -0.0626 -0.415926 -1.46475,
+							      -0.062585 -0.937566 -1.74258,
+							      0.477454 -1.87132 -6.6023,
+							      0.214366 -1.87132 -6.60231,
+							      0.441263 -0.495408 -8.43416,
+							      0.250751 -0.495408 -8.43417,
+							      0.414074 -0.461388 -8.95013,
+							      0.277994 -0.461388 -8.95014,
+							      0.436671 -2.14915 -7.37909,
+							      0.4548 -2.34193 -7.08992,
+							      0.241608 -2.34193 -7.08993,
+							      0.758426 -3.16939 -1.65658,
+							      -0.06259 -3.16939 -1.65662,
+							      0.758217 -3.03428 2.31419,
+							      -0.062799 -3.03428 2.31415,
+							      -0.062716 -1.54522 0.742657,
+							      -0.062569 -1.57261 -2.04875,
+							      0.7583 -1.54522 0.7427,
+							      0.758431 -0.937566 -1.74253,
+							      0.758447 -1.57261 -2.04871,
+							      0.100423 -2.54881 3.72509,
+							      -0.476109 -1.54522 0.742637,
+							      -0.47611 -0.830803 0.753977,
+							      -0.063333 -1.54522 0.742658,
+							      -0.063334 -0.830803 0.753998,
+							      -0.475978 -0.937566 -1.74259,
+							      -0.063202 -0.937566 -1.74257,
+							      1.17046 -0.830803 0.754063,
+							      0.757682 -0.830803 0.754041,
+							      1.17064 -1.59392 -2.71303,
+							      1.17046 -1.54522 0.742723,
+							      0.757683 -1.54522 0.742701,
+							      0.75783 -1.57261 -2.04871,
+							      1.17059 -0.937566 -1.74251,
+							      -0.475928 -1.57816 -2.70774,
+							      -0.475962 -1.57261 -2.04878,
+							      -0.063153 -0.955725 -2.674,
+							      -0.475929 -0.955725 -2.67402,
+							      -0.063186 -1.57261 -2.04875,
+							      -0.063152 -1.57816 -2.70772,
+							      1.17061 -1.57261 -2.04869,
+							      1.17064 -0.971488 -2.67932,
+							      0.757865 -1.59392 -2.71305,
+							      0.757814 -0.937566 -1.74253,
+							      0.757863 -0.971488 -2.67934,
+							      1.43188 0.68 -6.37806,
+							      1.43188 0.619 -6.37806,
+							      -2.79216 0.628 -5.63428,
+							      -2.79216 0.567 -5.63428,
+							      -5.55033 0.401 -2.35642,
+							      -5.55033 0.34 -2.35642,
+							      -5.54956 0.105 1.92358,
+							      -5.54956 0.044 1.92358,
+							      -0.744768 -0.173 5.94583,
+							      -0.744768 -0.234 5.94583,
+							      3.47927 -0.122 5.20305,
+							      3.47927 -0.183 5.20305,
+							      6.23667 0.341 -2.3568,
+							      6.23667 0.402 -2.3568,
+							      6.23644 0.044 1.9242,
+							      6.23644 0.105 1.9242,
+							      0.530062 -0.771 -9.83811,
+							      0.615062 -0.771 -9.8381,
+							      0.530039 -1.542 -9.3921,
+							      0.615039 -1.542 -9.3921,
+							      0.529995 -1.846 -8.5551,
+							      0.614995 -1.846 -8.5551,
+							      0.529951 -1.542 -7.7181,
+							      0.614951 -1.542 -7.7181,
+							      0.529928 -0.771 -7.2731,
+							      0.614928 -0.771 -7.2731,
+							      0.614928 -0.319 -7.2731,
+							      0.529951 0.453 -7.7181,
+							      0.614951 0.453 -7.7181,
+							      0.614995 0.757 -8.5551,
+							      0.529995 0.757 -8.5551,
+							      -2.79173 -0.122 5.20272,
+							      -2.79173 -0.183 5.20272 ]
+				    }
+
+				    creaseAngle	1
+				    coordIndex	[ 78, 171, 172, 63, -1, 74, 163, 164,
+						      67, -1, 62, 175, 63, 172, 64, 170,
+						      193, 65, 168, 66, 166, 67, 164, 68,
+						      162, 69, 70, 173, -1, 165, 74, 67,
+						      166, -1, 173, 70, 71, 174, -1, 175,
+						      62, 79, 176, -1, 167, 75, 66, 168,
+						      -1, 175, 176, 78, 63, -1, 73, 161,
+						      162, 68, -1, 77, 169, 170, 64, -1,
+						      62, 173, 174, 79, -1, 75, 165, 166,
+						      66, -1, 174, 71, 72, 161, 73, 163,
+						      74, 165, 75, 167, 76, 192, 169, 77,
+						      171, 78, 176, 79, -1, 163, 73, 68,
+						      164, -1, 171, 77, 64, 172, -1, 192,
+						      76, 65, 193, -1, 169, 192, 193, 170,
+						      -1, 161, 72, 69, 162, -1, 72, 71,
+						      70, 69, -1, 76, 167, 168, 65, -1,
+						      -1 ]
+			    }
+
+		    }
+	    }
+	]
+}
+Background {
+	groundAngle	[ 0.9, 1.5, 1.57 ]
+	groundColor	[ 0 0.8 0,
+			  0.174249 0.82 0.187362,
+			  0.467223 0.82 0.445801,
+			  0.621997 0.67 0.600279 ]
+	skyAngle	[ 0.1, 1.2, 1.57 ]
+	skyColor	[ 0.76238 0.8 0.1427,
+			  0.277798 0.219779 0.7,
+			  0.222549 0.390234 0.7,
+			  0.60094 0.662637 0.69 ]
+}
+DEF sqare_platform Transform {
+	translation	0 -0.432 0
+	scale	2 0.04 2
+	children [ 
+	    Shape {
+		    appearance	Appearance {
+			    material	Material {
+				    ambientIntensity	0.2
+				    diffuseColor	0.8 0.407144 0.297047
+			    }
+
+		    }
+
+		    geometry	Box {
+		    }
+
+	    }
+
+	    Transform {
+		    translation	0 0.031 0
+		    scale	0.5 1 0.5
+		    children Shape {
+			    appearance	Appearance {
+				    material	Material {
+					    diffuseColor	0.8 0.613697 0.365273
+				    }
+
+			    }
+
+			    geometry	Cylinder {
+			    }
+
+		    }
+	    }
+	]
+}
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/simulated_quad_simulink.slx b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/simulated_quad_simulink.slx
new file mode 100644
index 0000000000000000000000000000000000000000..81e0e6d616b7729468060d5731c24cb45b2dfc80
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/simulated_quad_simulink.slx differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/sl3dex_uav.slxc b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/sl3dex_uav.slxc
new file mode 100644
index 0000000000000000000000000000000000000000..c9a222e013aa35a04b993c149d999de55417c1fe
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/sl3dex_uav.slxc differ
diff --git a/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/vrheat_anim.avi b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/vrheat_anim.avi
new file mode 100644
index 0000000000000000000000000000000000000000..f59acba597652382d81f18cbaa3812aa0b1f8468
Binary files /dev/null and b/controls/Sim-nonlinear-quad-example/Sim-nonlinear-quad-example/vrheat_anim.avi differ
diff --git a/controls/model/CodeImplementation/Actuation/A_BE_System.m b/controls/model/CodeImplementation/Actuation/A_BE_System.m
new file mode 100644
index 0000000000000000000000000000000000000000..0ea6ce1e392906445e3dff60122f54b9b76c0a74
--- /dev/null
+++ b/controls/model/CodeImplementation/Actuation/A_BE_System.m
@@ -0,0 +1,30 @@
+% 
+
+classdef A_BE_System
+    
+    properties
+        B_omega
+        euler_angles
+    end
+    
+    methods
+        function obj = A_BE_System(B_omega,euler_angles)
+            obj.B_omega = B_omega;
+            obj.euler_angles = euler_angles;
+        end
+        
+        function euler_rates = A_BE(obj)
+            
+            phi = obj.euler_angles(1);
+            theta = obj.euler_angles(2);
+            
+            Aeb = [1,  sin(phi)*tan(theta), cos(phi)*tan(theta); ...
+                   0,      cos(phi)       ,        -sin(phi)   ; ...
+                   0,  sin(phi)/cos(theta), cos(phi)/cos(theta)];
+            
+               
+            euler_rates = Aeb * obj.B_omega;
+        end
+    end
+end
+
diff --git a/controls/model/CodeImplementation/Actuation/Actuation.m b/controls/model/CodeImplementation/Actuation/Actuation.m
new file mode 100644
index 0000000000000000000000000000000000000000..21bde4cc5c924303024574aa8147a3bd64c66e04
--- /dev/null
+++ b/controls/model/CodeImplementation/Actuation/Actuation.m
@@ -0,0 +1,89 @@
+% Implements the top level actuation block for the drone actuation system.
+%
+% Author: Gautham Ajith
+%
+classdef Actuation   
+    properties
+        A_BE_System
+        ESC_System
+        L_BE_System
+        L_BE_2
+        Motor_System
+        Rotor_System
+        Pmax
+        Pmin
+        Vb
+        w
+        dt
+        eu_angle
+        B_omega
+        B_Vo
+    end
+    
+    methods
+        function obj = Actuation(A_BE_System, ESC_System, L_BE_System, L_BE_2, Motor_System, Rotor_System, Pmax, Pmin, Vb)
+            obj.A_BE_System = A_BE_System;
+            obj.ESC_System = ESC_System();
+            obj.L_BE_System = L_BE_System;
+            obj.L_BE_2 = L_BE_2;
+            obj.Motor_System = Motor_System;
+            obj.Rotor_System = Rotor_System;
+            obj.Pmax = Pmax;
+            obj.Pmin = Pmin;
+            obj.Vb = Vb;
+            obj.w = 0;
+            obj.dt = 0;
+            obj.B_omega = 0;
+            obj.B_Vo = 0;
+        end
+        
+        function [B_omega, euler_angles, B_Vo, E_ro, B_vo_dot, B_g] = NextOutput(obj, m, Rm, Kv, Kq, Kd, If, Jreq, delta_t)
+            obj.dt = delta_t;
+            obj.Motor_System.Vb_Eff = obj.ESC_System.ESC(obj.ESC_System, obj.Pmax, obj.Pmin, obj.Vb);
+            w_dot = obj.Motor_System.Motor(obj.Motor_System, Rm, Kv, Kq, Kd, If, Jreq, obj.w);
+            obj.w = obj.integrator(w_dot, obj.dt, omega0_o, omega1_o, omega2_o, omega3_o);
+            B_Fg, B_g = obj.L_BE_System.L_BE(obj.L_BE_System);
+            B_omega_dot, B_vo_dot = obj.Rotor_System.rotor(obj, m, Kt, Kd, rhx, rhy, rhz, Jreq, Jxx, Jyy, Jzz, r_oc, Kh, delta_T);
+            obj.B_Vo = integrator(B_vo_dot, delta_t, x_vel_o, y_vel_o, z_vel_o);
+            obj.B_omega = integrator(B_omega_dot, delta_t, rollrate_o, pitchrate_o, yawrate_o);
+            B_omega = obj.B_omega;
+            B_Vo = obj.B_Vo;
+            euler_rates = obj.A_BE_System.A_BE(obj.A_BE_System);
+            euler_angles = integrator(euler_rates, delta_t, roll_o, pitch_o, yaw_o);
+            E_ro_dot = obj.L_BE_2_System.L_BE_2(obj.L_BE_2, obj.B_Vo);
+            E_ro = integrator(E_ro_dot, delta_t, x_o, y_o, z_o);
+
+
+
+
+            
+            
+
+
+
+        end
+
+        function output = integrator(input, delta_t, init_cond_1, init_cond_2, init_cond_3, init_cond_4)
+            if nargin < 5
+                x = input(1);
+                y = input(2);
+                z = input(3);
+                x_prime = int(x, 0, delta_t) +init_cond_1;
+                y_prime = int(y, 0, delta_t) + init_cond_2;
+                z_prime = int(z, 0, delta_t) + init_cond_3;
+                output = [x_prime, y_prime, z_prime];
+            else
+                o1 = input(1);
+                o2 = input(2);
+                o3 = input(3);
+                o4 = input(4);
+                o1_prime = int(o1, 0, delta_t) + init_cond_1;
+                o2_prime = int(o2, 0, delta_t) + init_cond_2;
+                o3_prime = int(o3, 0, delta_t) + init_cond_3;
+                o4_prime = int(o4, 0, delta_t) + init_cond_4;
+                output = [o1_prime, o2_prime, o3_prime, o4_prime];
+            end
+        end
+    end
+end
+
diff --git a/controls/model/CodeImplementation/Actuation/Actuation_Mat_temp.m b/controls/model/CodeImplementation/Actuation/Actuation_Mat_temp.m
new file mode 100644
index 0000000000000000000000000000000000000000..1f83108e0eb54b3cc4743b48f3a7ac774e7ee5fc
--- /dev/null
+++ b/controls/model/CodeImplementation/Actuation/Actuation_Mat_temp.m
@@ -0,0 +1,206 @@
+function [B_omega, euler_angles, B_vo, E_ro, B_vo_dot, B_g]= Actuation_Mat(P)
+
+    function Vb_eff   = ESC(P, Pmin, Pmax, Vb)
+        P1 = P(1);
+        P2 = P(2);
+        P3 = P(3);
+        P4 = P(4);
+        
+        % Define u_Pi for each of the rotors, limiting it to be greater than 0
+        u_P0 = (P1 - Pmin) / (Pmax - Pmin);
+        u_P1 = (P2 - Pmin) / (Pmax - Pmin);
+        u_P2 = (P3 - Pmin) / (Pmax - Pmin);
+        u_P3 = (P4 - Pmin) / (Pmax - Pmin);
+        
+        
+        % Determine the effective battery voltage from each ESC
+        Vb_eff_0 = u_P0 * Vb;
+        Vb_eff_1 = u_P1 * Vb;
+        Vb_eff_2 = u_P2 * Vb;
+        Vb_eff_3 = u_P3 * Vb;
+            
+        Vb_eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];
+    
+    function w_dot = motor(Vb_eff, w, Rm, Kv, Kq, Kd, If, Jreq)
+
+        % Define each motors effective battery voltage
+        Vb_eff_0 = Vb_eff(1);
+        Vb_eff_1 = Vb_eff(2);
+        Vb_eff_2 = Vb_eff(3);
+        Vb_eff_3 = Vb_eff(4);
+        
+        % Determine the angular velocity of each rotor from feedback
+        w_0 = w(1);
+        w_1 = w(2);
+        w_2 = w(3);
+        w_3 = w(4);
+        
+        % Determine angular acceleration of each rotor
+        w_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;
+        w_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;
+        w_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;
+        w_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;
+        
+        w_dot = [w_0_dot, w_1_dot, w_2_dot, w_3_dot];  
+
+    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, r_oc, Kh, delta_T)
+
+        % Create J vector
+        J = [Jxx,  0 ,  0 ; ...
+              0 , Jyy,  0 ; ...
+              0 ,  0 , Jzz;];
+          
+        r_oc_X = [0, -r_oc(3), r_oc(2); r_oc(3), 0, -r_oc(1); -r_oc(2), r_oc(1), 0];
+        
+        % Create r_hi vector
+        rh_0 = [-rhx; rhy; -rhz];
+        rh_1 = [rhx; rhy; -rhz];
+        rh_2 = [-rhx; -rhy; -rhz];
+        rh_3 = [rhx; -rhy; -rhz];
+        
+        % Calculate rotor hub velocity
+        vh_0 = B_vo + cross(B_omega,rh_0);
+        vh_1 = B_vo + cross(B_omega,rh_1); 
+        vh_2 = B_vo + cross(B_omega,rh_2); 
+        vh_3 = B_vo + cross(B_omega,rh_3); 
+        
+        % Define 3x3 Identity Matrix
+        I = eye(3);
+        
+        % Create gamma vectors
+        gamma_Ti = [0; 0; -1];
+        gamma_omega_03 = [0; 0; 1];  %Rotors 0 and 3 use this gamma_omega vector
+        gamma_omega_12 = [0; 0; -1]; %Rotors 1 and 2 use this gamma_omega vector
+        gamma_Hi = [ 1 0 0 ; 0 1 0 ; 0 0 0 ];
+        
+        % Define angular velocities for each rotor
+        w_0 = w(1);
+        w_1 = w(2);
+        w_2 = w(3);
+        w_3 = w(4);
+        
+        % Define angular acceleration for each rotor
+        w_0_dot = w_dot(1);
+        w_1_dot = w_dot(2);
+        w_2_dot = w_dot(3);
+        w_3_dot = w_dot(4);
+        
+        % Define the thrust force
+        T_0 = (Kt * w_0 * w_0 + delta_T * vh_0 * w_0) * gamma_Ti; 
+        T_1 = (Kt * w_1 * w_1 + delta_T * vh_1 * w_1) * gamma_Ti;
+        T_2 = (Kt * w_2 * w_2 + delta_T * vh_2 * w_2) * gamma_Ti;
+        T_3 = (Kt * w_3 * w_3 + delta_T * vh_3 * w_3) * gamma_Ti;
+        
+        % Define the in plane drag force
+        H_0 = -Kh * w_0 * gamma_Hi * vh_0;
+        H_1 = -Kh * w_1 * gamma_Hi * vh_1;
+        H_2 = -Kh * w_2 * gamma_Hi * vh_2;
+        H_3 = -Kh * w_3 * gamma_Hi * vh_3;
+        
+        % Define the rotor force in the z-direction from each rotor
+        B_Fr_0 = T_0 + H_0;
+        B_Fr_1 = T_1 + H_1;
+        B_Fr_2 = T_2 + H_2;
+        B_Fr_3 = T_3 + H_3;
+        
+        % Sum up the rotor forces in the z-direction from each vector to get the
+        % total body force in the z-direction
+        B_Fr = B_Fr_0 + B_Fr_1 + B_Fr_2 + B_Fr_3;
+        
+        % Define the in-plane drag and induced torque produced by each rotor
+         B_Q_d0 = -1 * Kd * w_0 * w_0 * gamma_omega_03;
+         B_Q_d1 = -1 * Kd * w_1 * w_1 * gamma_omega_12;
+         B_Q_d2 = -1 * Kd * w_2 * w_2 * gamma_omega_12;
+         B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;
+        
+        % Sum up the total in-plane drag and induced torque to get the total
+        % in-plane drag and induced torque on the body
+        B_Q_d = B_Q_d0 + B_Q_d1 + B_Q_d2 + B_Q_d3;
+        
+        % Define the force lever arm torque created from the force produced by each
+        % rotor in the z-direction
+        B_Q_F0 = cross( rh_0, B_Fr_0 );
+        B_Q_F1 = cross( rh_1, B_Fr_1 );
+        B_Q_F2 = cross( rh_2, B_Fr_2 );
+        B_Q_F3 = cross( rh_3, B_Fr_3 );
+        
+        B_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;
+        
+        % Define the change in angular momentum torque produced by each rotor 
+        B_Q_L0 = -1 * Jreq * ( cross(B_omega, w_0 * gamma_omega_03) + w_0_dot * gamma_omega_03 );
+        B_Q_L1 = -1 * Jreq * ( cross(B_omega, w_1 * gamma_omega_12) + w_1_dot * gamma_omega_12 ); 
+        B_Q_L2 = -1 * Jreq * ( cross(B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_omega_12 ); 
+        B_Q_L3 = -1 * Jreq * ( cross(B_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );
+        
+        % Sum up the total change in angular momentum torque produced by each rotor
+        B_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;
+            
+        % Define the total rotor system torque as the sum of the in-plane drag and
+        % induced torque, force lever arm torque, and change in angular momentum
+        % torques
+        B_Q = B_Q_d + B_Q_F + B_Q_L;
+        
+        % Define the body forces in the z-direction from each vector to get the
+        % total body force in the z-direction
+        B_F = B_Fr + B_Fg; 
+        
+        % Determine the dynamics of the system
+        M = [m * I , -m * r_oc_X; 
+            zeros(3,3), J];
+        
+        dynamics = M^-1*[B_F - m*cross(B_omega,B_vo) - m*cross(B_omega,cross(B_omega,r_oc)) ; ... 
+                  B_Q - cross(B_omega,J*B_omega) - cross(r_oc,B_F) ];
+        
+        % Define the body frame angular velocities
+        B_vo_dot = dynamics(1:3);
+        
+        % Define the body frame linear velocities
+        B_omega_dot = dynamics(4:6);
+
+    function E_Fg = gravity(m, g)
+
+        E_Fg = [0; 0; m*g];
+    
+    function [B_Fg, B_g]  = linear_earth_body_conversion(E_Fg, euler_angles, m)
+
+        phi = euler_angles(1);
+        theta = euler_angles(2);
+        psi = euler_angles(3);
+        
+        Lbe = [             cos(theta)*cos(psi)              ,          cos(theta)*sin(psi)                  ,     -sin(theta)    ; ...
+               sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...
+               cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];
+        
+        B_Fg = Lbe * E_Fg;
+        
+        B_g = B_Fg/m;
+
+    function euler_rates = angular_body_earth_conversion(B_omega, euler_angles)
+
+        phi = euler_angles(1);
+        theta = euler_angles(2);
+        
+        Aeb = [1,  sin(phi)*tan(theta), cos(phi)*tan(theta); ...
+               0,      cos(phi)       ,        -sin(phi)   ; ...
+               0,  sin(phi)/cos(theta), cos(phi)/cos(theta)];
+        
+           
+        euler_rates = Aeb * B_omega;
+  
+    function E_ro  = linear_body_earth_conversion(B_vo, euler_angles)
+
+        euler_rates = zeros(3,1);
+        E_ro = zeros(3,1);
+        
+        phi = euler_angles(1);
+        theta = euler_angles(2);
+        psi = euler_angles(3);
+        
+        Leb = [cos(theta)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ...
+               cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi); ...
+                   -sin(theta)    ,                sin(phi)*cos(theta)            ,                 cos(phi)*cos(theta)           ];
+        
+        E_ro = Leb * B_vo;
+    
+
+    
\ No newline at end of file
diff --git a/controls/model/CodeImplementation/Actuation/ESC_System.m b/controls/model/CodeImplementation/Actuation/ESC_System.m
new file mode 100644
index 0000000000000000000000000000000000000000..eae78c6da8d5a6ec9366f3ac7e827b9ef35c30f3
--- /dev/null
+++ b/controls/model/CodeImplementation/Actuation/ESC_System.m
@@ -0,0 +1,39 @@
+% This class is the code representation of the previous ESC_System Simulink
+% Block which was in the Actuator Block
+%
+% Author Gautham Ajith
+classdef ESC_System
+   
+    properties
+        P
+    end
+    
+    methods
+        function obj = ESC_System(P)
+            obj.P = P;
+        end
+        
+        function Vb_eff   = ESC(obj, Pmin, Pmax, Vb)
+            P1 = obj.P(1);
+            P2 = obj.P(2);
+            P3 = obj.P(3);
+            P4 = obj.P(4);
+            
+            % Define u_Pi for each of the rotors, limiting it to be greater than 0
+            u_P0 = (P1 - Pmin) / (Pmax - Pmin);
+            u_P1 = (P2 - Pmin) / (Pmax - Pmin);
+            u_P2 = (P3 - Pmin) / (Pmax - Pmin);
+            u_P3 = (P4 - Pmin) / (Pmax - Pmin);
+            
+            
+            % Determine the effective battery voltage from each ESC
+            Vb_eff_0 = u_P0 * Vb;
+            Vb_eff_1 = u_P1 * Vb;
+            Vb_eff_2 = u_P2 * Vb;
+            Vb_eff_3 = u_P3 * Vb;
+                
+            Vb_eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];            
+        end
+    end
+end
+
diff --git a/controls/model/CodeImplementation/Actuation/L_BE_System.m b/controls/model/CodeImplementation/Actuation/L_BE_System.m
new file mode 100644
index 0000000000000000000000000000000000000000..58b36f119da36f6d71d867e17d0e6f09fe54b429
--- /dev/null
+++ b/controls/model/CodeImplementation/Actuation/L_BE_System.m
@@ -0,0 +1,54 @@
+% This class represents the previous Simulink Block 
+% linear_earth_body_conversion and gravity block subsystem 
+%
+% Author Gautham Ajith
+
+classdef L_BE_System
+    
+    properties
+        E_Fg
+        B_vo
+        euler_angles
+    end
+    
+    methods
+        function obj = L_BE_System(g, m, euler_angles, B_vo)
+            if nargin < 3
+                obj.E_Fg = [0; 0; m*g];
+            else
+                obj.B_vo = B_vo;        
+            end
+            obj.euler_angles = euler_angles;
+        end
+        
+        function [B_Fg, B_g] = L_BE(obj)
+            phi = obj.euler_angles(1);
+            theta = obj.euler_angles(2);
+            psi = obj.euler_angles(3);
+            
+            Lbe = [             cos(theta)*cos(psi)              ,          cos(theta)*sin(psi)                  ,     -sin(theta)    ; ...
+                   sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...
+                   cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];
+            
+            B_Fg = Lbe * obj.E_Fg;
+            
+            B_g = B_Fg/m;
+        end
+
+        function E_ro  = L_BE_2(obj, B_vo)
+            euler_rates = zeros(3,1);
+            E_ro = zeros(3,1);
+            
+            phi = obj.euler_angles(1);
+            theta = obj.euler_angles(2);
+            psi = obj.euler_angles(3);
+            
+            Leb = [cos(theta)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ...
+                   cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi); ...
+                       -sin(theta)    ,                sin(phi)*cos(theta)            ,                 cos(phi)*cos(theta)           ];
+            
+            E_ro = Leb * B_vo;
+        end
+    end
+end
+
diff --git a/controls/model/CodeImplementation/Actuation/Motor_System.m b/controls/model/CodeImplementation/Actuation/Motor_System.m
new file mode 100644
index 0000000000000000000000000000000000000000..439e2b0b49b9568dad078f920c0792cadf076b31
--- /dev/null
+++ b/controls/model/CodeImplementation/Actuation/Motor_System.m
@@ -0,0 +1,42 @@
+% This class represents the code implementation of the previous simulink
+% block of the Motor_System in the Actuator Block.
+% 
+% Author Gautham Ajith
+
+classdef Motor_System
+    
+    properties
+        Vb_eff
+        w
+    end
+    
+    methods
+        function obj = Motor_System(Vb_eff)
+            obj.Vb_eff = Vb_eff;
+        end
+        
+        function w_dot = motor(obj, Rm, Kv, Kq, Kd, If, Jreq, w)
+    
+            % Define each motors effective battery voltage
+            Vb_eff_0 = obj.Vb_eff(1);
+            Vb_eff_1 = obj.Vb_eff(2);
+            Vb_eff_2 = obj.Vb_eff(3);
+            Vb_eff_3 = obj.Vb_eff(4);
+            
+            % Determine the angular velocity of each rotor from feedback
+            w_0 = w(1);
+            w_1 = w(2);
+            w_2 = w(3);
+            w_3 = w(4);
+            
+            % Determine angular acceleration of each rotor
+            w_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;
+            w_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;
+            w_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;
+            w_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;
+            
+            w_dot = [w_0_dot, w_1_dot, w_2_dot, w_3_dot];
+        end
+    end
+end
+
diff --git a/controls/model/CodeImplementation/Actuation/Rotor_System.m b/controls/model/CodeImplementation/Actuation/Rotor_System.m
new file mode 100644
index 0000000000000000000000000000000000000000..79ed523c88ab7a69c1c28fae9190b41ac4cbc30c
--- /dev/null
+++ b/controls/model/CodeImplementation/Actuation/Rotor_System.m
@@ -0,0 +1,144 @@
+% This class represents the previous Simulink Block Rotor_System which is
+% in the Actuation block
+%
+% Author Gautham Ajith
+classdef Rotor_System
+    
+    properties
+        w_dot
+        w
+        B_Fg
+        B_omega
+        B_vo
+    end
+    
+    methods
+        function obj = Rotor_System(w_dot, w, B_Fg, B_omega, B_vo)
+            %UNTITLED Construct an instance of this class
+            %   Detailed explanation goes here
+            obj.w_dot = w_dot;
+            obj.w = w;
+            obj.B_Fg = B_Fg;
+            obj.B_omega = B_omega;
+            obj.B_vo = B_vo;
+        end
+        
+        function [B_omega_dot, B_vo_dot] = rotor(obj, m, Kt, Kd, rhx, rhy, rhz, Jreq, Jxx, Jyy, Jzz, r_oc, Kh, delta_T)
+            %METHOD1 Summary of this method goes here
+            %   Detailed explanation goes here
+            
+            % Create J vector
+            J = [Jxx,  0 ,  0 ; ...
+                  0 , Jyy,  0 ; ...
+                  0 ,  0 , Jzz;];
+              
+            r_oc_X = [0, -r_oc(3), r_oc(2); r_oc(3), 0, -r_oc(1); -r_oc(2), r_oc(1), 0];
+            
+            % Create r_hi vector
+            rh_0 = [-rhx; rhy; -rhz];
+            rh_1 = [rhx; rhy; -rhz];
+            rh_2 = [-rhx; -rhy; -rhz];
+            rh_3 = [rhx; -rhy; -rhz];
+            
+            % Calculate rotor hub velocity
+            vh_0 = obj.B_vo + cross(obj.B_omega,rh_0);
+            vh_1 = obj.B_vo  + cross(obj.B_omega,rh_1); 
+            vh_2 = obj.B_vo  + cross(obj.B_omega,rh_2); 
+            vh_3 = obj.B_vo  + cross(obj.B_omega,rh_3); 
+            
+            % Define 3x3 Identity Matrix
+            I = eye(3);
+            
+            % Create gamma vectors
+            gamma_Ti = [0; 0; -1];
+            gamma_omega_03 = [0; 0; 1];  %Rotors 0 and 3 use this gamma_omega vector
+            gamma_omega_12 = [0; 0; -1]; %Rotors 1 and 2 use this gamma_omega vector
+            gamma_Hi = [ 1 0 0 ; 0 1 0 ; 0 0 0 ];
+            
+            % Define angular velocities for each rotor
+            w_0 = obj.w(1);
+            w_1 = obj.w(2);
+            w_2 = obj.w(3);
+            w_3 = obj.w(4);
+            
+            % Define angular acceleration for each rotor
+            w_0_dot = obj.w_dot(1);
+            w_1_dot = obj.w_dot(2);
+            w_2_dot = obj.w_dot(3);
+            w_3_dot = obj.w_dot(4);
+            
+            % Define the thrust force
+            T_0 = (Kt * w_0 * w_0 + delta_T * vh_0 * w_0) * gamma_Ti; 
+            T_1 = (Kt * w_1 * w_1 + delta_T * vh_1 * w_1) * gamma_Ti;
+            T_2 = (Kt * w_2 * w_2 + delta_T * vh_2 * w_2) * gamma_Ti;
+            T_3 = (Kt * w_3 * w_3 + delta_T * vh_3 * w_3) * gamma_Ti;
+            
+            % Define the in plane drag force
+            H_0 = -Kh * w_0 * gamma_Hi * vh_0;
+            H_1 = -Kh * w_1 * gamma_Hi * vh_1;
+            H_2 = -Kh * w_2 * gamma_Hi * vh_2;
+            H_3 = -Kh * w_3 * gamma_Hi * vh_3;
+            
+            % Define the rotor force in the z-direction from each rotor
+            B_Fr_0 = T_0 + H_0;
+            B_Fr_1 = T_1 + H_1;
+            B_Fr_2 = T_2 + H_2;
+            B_Fr_3 = T_3 + H_3;
+            
+            % Sum up the rotor forces in the z-direction from each vector to get the
+            % total body force in the z-direction
+            B_Fr = B_Fr_0 + B_Fr_1 + B_Fr_2 + B_Fr_3;
+            
+            % Define the in-plane drag and induced torque produced by each rotor
+             B_Q_d0 = -1 * Kd * w_0 * w_0 * gamma_omega_03;
+             B_Q_d1 = -1 * Kd * w_1 * w_1 * gamma_omega_12;
+             B_Q_d2 = -1 * Kd * w_2 * w_2 * gamma_omega_12;
+             B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;
+            
+            % Sum up the total in-plane drag and induced torque to get the total
+            % in-plane drag and induced torque on the body
+            B_Q_d = B_Q_d0 + B_Q_d1 + B_Q_d2 + B_Q_d3;
+            
+            % Define the force lever arm torque created from the force produced by each
+            % rotor in the z-direction
+            B_Q_F0 = cross( rh_0, B_Fr_0 );
+            B_Q_F1 = cross( rh_1, B_Fr_1 );
+            B_Q_F2 = cross( rh_2, B_Fr_2 );
+            B_Q_F3 = cross( rh_3, B_Fr_3 );
+            
+            B_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;
+            
+            % Define the change in angular momentum torque produced by each rotor 
+            B_Q_L0 = -1 * Jreq * ( cross(obj.B_omega, w_0 * gamma_omega_03) + w_0_dot * gamma_omega_03 );
+            B_Q_L1 = -1 * Jreq * ( cross(obj.B_omega, w_1 * gamma_omega_12) + w_1_dot * gamma_omega_12 ); 
+            B_Q_L2 = -1 * Jreq * ( cross(obj.B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_omega_12 ); 
+            B_Q_L3 = -1 * Jreq * ( cross(obj.B_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );
+            
+            % Sum up the total change in angular momentum torque produced by each rotor
+            B_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;
+                
+            % Define the total rotor system torque as the sum of the in-plane drag and
+            % induced torque, force lever arm torque, and change in angular momentum
+            % torques
+            B_Q = B_Q_d + B_Q_F + B_Q_L;
+            
+            % Define the body forces in the z-direction from each vector to get the
+            % total body force in the z-direction
+            B_F = B_Fr + obj.B_Fg; 
+            
+            % Determine the dynamics of the system
+            M = [m * I , -m * r_oc_X; 
+                zeros(3,3), J];
+            
+            dynamics = M^-1*[B_F - m*cross(obj.B_omega,obj.B_vo) - m*cross(obj.B_omega,cross(obj.B_omega,r_oc)) ; ... 
+                      B_Q - cross(obj.B_omega,J*obj.B_omega) - cross(r_oc,B_F) ];
+            
+            % Define the body frame angular velocities
+            B_vo_dot = dynamics(1:3);
+            
+            % Define the body frame linear velocities
+            B_omega_dot = dynamics(4:6);
+        end
+    end
+end
+
diff --git a/controls/model/CodeImplementation/Controller/DroneControlSystem.m b/controls/model/CodeImplementation/Controller/DroneControlSystem.m
new file mode 100644
index 0000000000000000000000000000000000000000..001f9cc40a134995a2260b8b26f9dffcd0b824b4
--- /dev/null
+++ b/controls/model/CodeImplementation/Controller/DroneControlSystem.m
@@ -0,0 +1,111 @@
+% Implements the top level control block for the drone control system.
+% Implements a switch between a PID controller and the LQR controller.
+%
+% Author: Austin Beinder
+%
+
+classdef DroneControlSystem
+    properties
+        drone_pid_controller
+        signal_mixer
+        pmax
+        pmin
+        lqr_k
+
+    end
+    methods 
+        function obj = DroneControlSystem(drone_pid_controller, signal_mixer, pmax, pmin, lqr_k)
+           
+            obj.drone_pid_controller = drone_pid_controller;
+            obj.signal_mixer = signal_mixer;
+            obj.pmax = pmax;
+            obj.pmin = pmin;
+            obj.lqr_k = lqr_k;
+
+            return;
+        end
+        
+        % Equivalent to nextOutput in RealTimePIDController
+        function [P, controller] = nextOutputMainController(controller, setpoints, euler_angles_filtered, euler_rates, current_position, delta_t)
+            
+            x_setpoint = setpoints(1);
+            y_setpoint = setpoints(2);
+            z_setpoint = setpoints(3);
+            yaw_setpoint = setpoints(4);
+
+            x_position = current_position(1);
+            y_position = current_position(2);
+            z_position = current_position(3);
+
+            roll = euler_angles_filtered(1);
+            pitch = euler_angles_filtered(2); % not super sure im getting these right
+            yaw = euler_angles_filtered(3);
+
+            roll_rate = euler_rates(1);
+            pitch_rate = euler_rates(2);
+            yaw_rate = euler_rates(3);
+
+            [heightControlled, y_controlled, x_controlled, yaw_controlled, controller.drone_pid_controller] = controller.drone_pid_controller.nextOutput(z_setpoint, z_position, y_setpoint, y_position, roll, roll_rate, ...
+                x_setpoint, x_position, pitch, pitch_rate, yaw_setpoint, yaw, yaw_rate, delta_t);
+            
+            P = [heightControlled, y_controlled, x_controlled, yaw_controlled];
+            
+        end
+
+        function [P, setpoint_error] = nextOutputErrorController(controller, setpoints, euler_angles_filtered, euler_rates, current_position, velocity)
+            
+            vector1 = [velocity, euler_rates, euler_angles_filtered, current_position];
+            vector2 = [0, 0, 0, 0, 0, 0, setpoints(1), setpoints(2), setpoints(3), 0, 0, setpoints(4)];
+            
+            setpoint_error = vector1 - vector2;
+            p1 = setpoint_error .* controller.lqr_k;
+            p2 = controller.saturation(p1, [20000, 20000, 20000, 20000], [-20000, -20000, -20000, -20000]);
+            
+            P = -p2;
+
+
+        end
+        
+        % Top level control system function, muxes between LQR controller
+        % and PID controller.
+        function [P, setpoint_error, controller] = nextOutput(controller, setpoints, euler_angles_filtered, euler_rates, current_position, velocity, throttle_command, y_controlled, x_controlled, yaw_controlled, lqr_switch, delta_t)
+            
+            [p11, controller] = controller.nextOutputMainController(setpoints, euler_angles_filtered, euler_rates, current_position, delta_t); 
+            [p12, setpoint_error] = controller.nextOutputErrorController(setpoints, euler_angles_filtered, euler_rates, current_position, velocity);
+
+            if (lqr_switch == 1)
+                p2 = p11;
+            else
+                p2 = p12;
+            end
+
+            p3 = p2 * controller.signal_mixer;
+            
+            external_inputs = [throttle_command, y_controlled, x_controlled, yaw_controlled];
+
+            p4 = p3 + external_inputs;
+
+            P = controller.saturation(p4, controller.pmax, controller.pmin);
+
+        end
+
+        % Mimics the saturation block in simulink
+        function output = saturation(~, input, upper, lower)
+            
+            l = length(input);
+            output = zeros(1,l);
+            for i = 1:length(input)
+                
+                if input(i) > upper
+                    output(i) = upper;
+                elseif input(i) < lower
+                    output(i) = lower;
+                else
+                    output(i) = input(i);
+                end    
+            end
+        end
+
+    end
+
+end
\ No newline at end of file
diff --git a/controls/model/CodeImplementation/Controller/DronePIDController.m b/controls/model/CodeImplementation/Controller/DronePIDController.m
new file mode 100644
index 0000000000000000000000000000000000000000..ed3f45e1dd4c27f29a0aa7986544367902c57a4b
--- /dev/null
+++ b/controls/model/CodeImplementation/Controller/DronePIDController.m
@@ -0,0 +1,138 @@
+% This class represents a code implementation of the previous block diagram
+% of the quadcopter PID controller. It uses several nested PID controllers
+% to achieve control of x, y, z and yaw.
+%
+% Author: Austin Beinder
+%
+
+classdef DronePIDController
+    properties
+        z_pid_controller
+
+        z_max
+        z_min
+
+        y_pid 
+        y_pid1
+        y_vel_pid
+        roll_pid
+        roll_rate_pid
+
+        y_max
+        y_min
+
+        x_pid
+        y_pid2
+        x_vel_pid
+        pitch_pid
+        pitch_rate_pid
+
+        x_max
+        x_min
+
+
+        yaw_pid
+        yaw_rate_pid
+        yaw_max
+        yaw_min
+
+    end
+    methods 
+        function obj = DronePIDController(z_pid, z_max, z_min, y_pid, y_pid1, y_vel_pid, roll_pid, roll_rate_pid, y_max, y_min, ...
+                x_pid, y_pid2, x_vel_pid, pitch_pid, pitch_rate_pid, x_max, x_min, yaw_pid, yaw_rate_pid, yaw_max, yaw_min)
+           
+            obj.z_pid_controller = z_pid;
+            obj.z_max = z_max;
+            obj.z_min = z_min;
+
+            obj.y_pid = y_pid;
+            obj.y_pid1 = y_pid1;
+            obj.y_vel_pid = y_vel_pid;
+            obj.roll_pid = roll_pid;
+            obj.roll_rate_pid = roll_rate_pid;
+            obj.y_max = y_max;
+            obj.y_min = y_min;
+
+
+            obj.x_pid = x_pid;
+            obj.y_pid2 = y_pid2;
+            obj.x_vel_pid = x_vel_pid;
+            obj.pitch_pid = pitch_pid;
+            obj.pitch_rate_pid = pitch_rate_pid;
+            obj.x_max = x_max;
+            obj.x_min = x_min;
+
+            obj.yaw_pid = yaw_pid;
+            obj.yaw_rate_pid = yaw_rate_pid;
+            obj.yaw_max = yaw_max;
+            obj.yaw_min = yaw_min;
+
+            return;
+        end
+        
+        % Equivalent to nextOutput in RealTimePIDController
+        function [heightControlled, y_controlled, x_controlled, yaw_controlled, controller] = nextOutput(controller, z_setpoint, z_position, y_setpoint, y_position, roll, roll_rate, ...
+                x_setpoint, x_position, pitch, pitch_rate, yaw_setpoint, yaw, yaw_rate, delta_t)
+            
+            % ------------- Height Controller -----------
+            z_error = z_setpoint - z_position;
+            [z_output, controller.z_pid_controller] = controller.z_pid_controller.pi_minus_d(z_error, z_position, delta_t);
+            heightControlled = controller.saturation(z_output, controller.z_max, controller.z_min);
+            
+            % -------------- Y Controller ---------
+            y_error = y_setpoint - y_position;
+            [y_output1, controller.y_pid] = controller.y_pid.pi_minus_d(y_error, y_position, delta_t);
+            [y_output2, controller.y_pid1] = controller.y_pid1.pi_minus_d(y_error, y_position, delta_t);
+
+            y_vel_error = y_output1 - y_output2;
+            [roll_setpoint, controller.y_vel_pid] = controller.y_vel_pid.pi_minus_d(y_vel_error, y_output2, delta_t);
+            
+            roll_error = roll_setpoint - roll;
+            [roll_rate_setpoint, controller.roll_pid] = controller.roll_pid.pi_minus_d(roll_error, roll_setpoint, delta_t);
+
+            roll_rate_error = roll_rate_setpoint - roll_rate;
+            [y_motor_command, controller.roll_rate_pid] = controller.roll_rate_pid.pi_minus_d(roll_rate_error, roll_rate, delta_t);
+            y_controlled = controller.saturation(y_motor_command, controller.y_max, controller.y_min);
+            
+            % --------------- X Controller ---------
+            x_error = x_setpoint - x_position;
+            [x_output1, controller.x_pid] = controller.x_pid.pi_minus_d(x_error, x_position, delta_t);
+            [x_output2, controller.y_pid2] = controller.y_pid2.pi_minus_d(x_error, x_position, delta_t);
+
+            x_vel_error = x_output1 - x_output2;
+            [pitch_setpoint, controller.x_vel_pid] = controller.x_vel_pid.pi_minus_d(x_vel_error, x_output2, delta_t);
+            
+            pitch_error = pitch_setpoint - pitch;
+            [pitch_rate_setpoint, controller.pitch_pid] = controller.pitch_pid.pi_minus_d(pitch_error, pitch, delta_t);
+
+            pitch_rate_error = pitch_rate_setpoint - pitch_rate;
+            [x_motor_command, controller.pitch_rate_pid] = controller.pitch_rate_pid.pi_minus_d(pitch_rate_error, pitch_rate, delta_t);
+
+            x_controlled = controller.saturation(x_motor_command, controller.x_max, controller.y_max);
+
+            % --------------- Yaw Controller -------
+            yaw_error = yaw_setpoint - yaw;
+            [yaw_setpoint, controller.yaw_pid] = controller.yaw_pid.pi_minus_d(yaw_error, yaw, delta_t);
+
+            yaw_rate_error = yaw_setpoint - yaw_rate;
+            [yaw_motor_command, controller.yaw_rate_pid] = controller.yaw_rate_pid.pi_minus_d(yaw_rate_error, yaw_rate, delta_t);
+
+            yaw_controlled = controller.saturation(yaw_motor_command, controller.yaw_max, controller.yaw_min);
+
+        end
+        
+        % Mimics the saturation block in simulink
+        function output = saturation(~, input, upper, lower)
+            
+            if input > upper
+                output = upper;
+            elseif input < lower
+                output = lower;
+            else
+                output = input;
+            end
+        end
+
+    end
+
+end
\ No newline at end of file
diff --git a/controls/model/CodeImplementation/Controller/PIminusDController.m b/controls/model/CodeImplementation/Controller/PIminusDController.m
new file mode 100644
index 0000000000000000000000000000000000000000..629867b3fb67469d6c35bc91bbbf383fa37d2e3d
--- /dev/null
+++ b/controls/model/CodeImplementation/Controller/PIminusDController.m
@@ -0,0 +1,30 @@
+classdef PIminusDController
+    properties
+        pi_controller
+        d_controller
+    end
+    methods 
+        function obj = PIminusDController(P, I, D, ts)
+           
+
+            pi_c = RealTimePIDController(P, I, 0);
+            d_c = RealTimeDerivativeController(D);
+
+            obj.pi_controller = pi_c;
+            obj.d_controller = d_c;
+
+            return;
+        end
+        
+        % Equivalent to nextOutput in RealTimePIDController
+        function [setpoint, controller] = pi_minus_d(controller, error, value, delta_t)
+            [output1, controller.pi_controller] = controller.pi_controller.nextOutput(error, delta_t);
+
+            [output2, controller.d_controller] = controller.d_controller.nextOutput(value, delta_t);
+
+            setpoint = output1 - output2;
+        end
+
+    end
+
+end
\ No newline at end of file
diff --git a/controls/model/CodeImplementation/Controller/RealTimeDerivativeController.m b/controls/model/CodeImplementation/Controller/RealTimeDerivativeController.m
new file mode 100644
index 0000000000000000000000000000000000000000..592dce25dc302689df39200b4e04b32656de6d95
--- /dev/null
+++ b/controls/model/CodeImplementation/Controller/RealTimeDerivativeController.m
@@ -0,0 +1,32 @@
+% This implements a D controller in the time domain. 
+%
+% Author: Austin Beinder
+%
+
+classdef RealTimeDerivativeController
+    properties
+        D {mustBeNumeric}
+        input_last {mustBeNumeric}
+    end
+    methods 
+        function obj = RealTimeDerivativeController(d)
+            
+            obj.D = d;
+            obj.input_last = 0;
+
+        end
+
+        function [output, controller] = nextOutput(controller, input, delta_t)
+            
+            difference = input - controller.input_last;
+            slope = difference / delta_t;
+
+            output = controller.D * slope;
+            controller.input_last = input;
+
+
+        end
+
+
+    end
+end
\ No newline at end of file
diff --git a/controls/model/CodeImplementation/Controller/RealTimePIDController.m b/controls/model/CodeImplementation/Controller/RealTimePIDController.m
new file mode 100644
index 0000000000000000000000000000000000000000..18c78674e80c103b7c94d6477470557a02f1a976
--- /dev/null
+++ b/controls/model/CodeImplementation/Controller/RealTimePIDController.m
@@ -0,0 +1,50 @@
+% This implements a PID controller in the time domain. All equations are 
+% taken from the wikipedia "Discrete implementation" section.
+%
+% https://en.wikipedia.org/wiki/PID_controller#Discrete_implementation
+%
+% Author: Austin Beinder
+%
+
+classdef RealTimePIDController
+    properties
+        P {mustBeNumeric}
+        I {mustBeNumeric}
+        D {mustBeNumeric}
+        input_last {mustBeNumeric}
+        input_second_2last {mustBeNumeric}
+        output_last {mustBeNumeric}
+    end
+    methods 
+        function obj = RealTimePIDController(p, i, d)
+            
+            obj.P = p;
+            obj.I = i;
+            obj.D = d;
+            obj.input_last = 0;
+            obj.input_second_2last = 0;
+            obj.output_last = 0;
+
+        end
+
+        function [output, pid] = nextOutput(pid, input, delta_t)
+            
+            Ti = pid.P / pid.I;
+            Td = pid.D / pid.P;
+
+            term1 = (1 + (delta_t/Ti) + (Td/delta_t)) * input;
+            term2 = (-1 - (2*Td/delta_t)) * pid.input_last;
+            term3 = ((Td/delta_t)) * pid.input_second_2last;
+
+            output = pid.output_last + pid.P * (term1 + term2 + term3);
+
+            pid.input_last = input;
+            pid.input_second_2last = pid.input_last;
+            pid.output_last = output;
+
+
+        end
+
+
+    end
+end
\ No newline at end of file
diff --git a/controls/model/CodeImplementation/Sensors/IMUModel.m b/controls/model/CodeImplementation/Sensors/IMUModel.m
new file mode 100644
index 0000000000000000000000000000000000000000..fcadf798442e5737d9ff7904ab77f6645331fca2
--- /dev/null
+++ b/controls/model/CodeImplementation/Sensors/IMUModel.m
@@ -0,0 +1,99 @@
+% 
+%
+% Author: Austin Beinder
+%
+
+classdef IMUModel
+    properties
+        accelerometer_sample_time
+        accelerometer_transfer_function
+        accelerometer_noise
+        gyroscope_sample_time
+        gyroscope_noise
+        gyroscope_transfer_function
+        accel_sampler_out
+        gyro_sampler_out
+        time
+        accelerometer_tf_state
+        gyroscope_tf_state
+        accel_tf_b
+        accel_tf_a
+        gyro_tf_b
+        gyro_tf_a
+
+    end
+    methods 
+        function obj = IMUModel(accelerometer_sample_time, ...
+                accelerometer_transfer_function, ...
+                accelerometer_noise, ...
+                gyroscope_sample_time, ...
+                gyroscope_noise, ...
+                gyroscope_transfer_function)
+            
+            obj.accelerometer_sample_time = accelerometer_sample_time;
+            obj.accelerometer_transfer_function = accelerometer_transfer_function;
+            obj.accelerometer_noise = accelerometer_noise;
+            obj.gyroscope_sample_time = gyroscope_sample_time;
+            obj.gyroscope_noise = gyroscope_noise;
+            obj.gyroscope_transfer_function = gyroscope_transfer_function;
+            obj.time = 0;
+
+            obj.accel_sampler_out = zeros(1, 3);
+            obj.gyro_sampler_out = zeros(1, 3);
+
+            obj.accelerometer_tf_state = 0;
+            obj.gyroscope_tf_state = 0;
+
+            obj.accel_tf_b = [0.749 0];
+            obj.accel_tf_a = [-0.251 1];
+            obj.gyro_tf_b = [0.7327 0];
+            obj.gyro_tf_a = [-0.2673 1];
+
+        end
+
+        function [accelerometer, gyroscope, imu] = nextOutput(imu, B_vo_dot, B_vo, B_Omega, B_g, g, r_oc, delta_t)
+            
+            [accelReading, gyroReading] = IdealIMU(B_vo_dot, B_vo, B_Omega, B_g, g, r_oc);
+            
+            [imu.accel_sampler_out, imu] = imu.sampler(imu.accelerometer_sample_time, accelReading, imu.accel_sampler_out, delta_t);
+            [imu.gyro_sampler_out, imu] = imu.sampler(imu.gyroscope_sample_time, gyroReading, imu.accel_sampler_out, delta_t);
+            
+            noisy_accel = imu.accel_sampler_out + mvnrnd([0,0,0],imu.accelerometer_noise);
+            noisy_gyro = imu.gyro_sampler_out + mvnrnd([0,0,0],imu.gyroscope_noise);
+
+            [filtered_accel, imu.accelerometer_tf_state] = filter(imu.accel_tf_b, imu.accel_tf_a, noisy_accel, imu.accelerometer_tf_state);
+            [filtered_gyro, imu.gyroscope_tf_state] = filter(imu.gyro_tf_b, imu.gyro_tf_a, noisy_gyro, imu.gyroscope_tf_state);
+            
+            accelerometer = quantization(2.4400e-04, filtered_accel);
+            gyroscope = quantization(1.1e-3, filtered_gyro);
+
+        end
+
+        function [output, imu] = sampler(imu, sample_rate, input_vector, current_output, delta_t)
+        
+            new_time = imu.time + delta_t;
+
+            if (new_time > sample_rate)
+                imu.time = new_time - sample_rate;
+                output = input_vector;
+            else
+                imu.time = new_time;
+                output = current_output;
+            end
+
+        end
+    end
+end
+
+function output = quantization(quantization_rate, input_vector)
+            
+    output = zeros(1, length(input_vector));
+
+    for i = 1:length(input_vector)
+        
+        output(i) = quantization_rate * ...
+            round(input_vector(i) / quantization_rate);
+
+    end
+
+end
\ No newline at end of file
diff --git a/controls/model/CodeImplementation/Sensors/IdealIMU.m b/controls/model/CodeImplementation/Sensors/IdealIMU.m
new file mode 100644
index 0000000000000000000000000000000000000000..95942b60b9f4782c6b1c7823216a653c0e4e696d
--- /dev/null
+++ b/controls/model/CodeImplementation/Sensors/IdealIMU.m
@@ -0,0 +1,11 @@
+function [accelReading, gyroReading] = idealIMU(B_vo_dot, B_vo, B_Omega, B_g, g, r_oc)
+%#codegen
+
+a = B_vo_dot + cross(B_Omega,B_vo); % body frame acceleration 
+
+accelReading = (a - B_g)/g ; % accelerometer reading (ideal)
+
+gyroReading = B_Omega ; % gyroscope reading (ideal) 
+
+end
+
diff --git a/controls/model/Quadcopter_Model.slx b/controls/model/Quadcopter_Model.slx
index e7f7ad3500d97b1b851d355dcadb8fac2467ade9..e8fd2b1a76aa34aae81204a7e998878e589df4fc 100644
Binary files a/controls/model/Quadcopter_Model.slx and b/controls/model/Quadcopter_Model.slx differ
diff --git a/controls/model/Quadcopter_Model.slx.r2017a b/controls/model/Quadcopter_Model.slx.r2017a
new file mode 100644
index 0000000000000000000000000000000000000000..e7f7ad3500d97b1b851d355dcadb8fac2467ade9
Binary files /dev/null and b/controls/model/Quadcopter_Model.slx.r2017a differ
diff --git a/controls/model/Quadcopter_Model.slx.r2021b b/controls/model/Quadcopter_Model.slx.r2021b
new file mode 100644
index 0000000000000000000000000000000000000000..a308ba90647370bac0b5dee839b1a2dd1bdcdb60
Binary files /dev/null and b/controls/model/Quadcopter_Model.slx.r2021b differ
diff --git a/controls/model/Quadcopter_Model.slxc b/controls/model/Quadcopter_Model.slxc
new file mode 100644
index 0000000000000000000000000000000000000000..21a4d48913aafef81fd80f84395e43d80faed857
Binary files /dev/null and b/controls/model/Quadcopter_Model.slxc differ
diff --git a/controls/model/SFB__actuation_mat__SFB.mat b/controls/model/SFB__actuation_mat__SFB.mat
new file mode 100644
index 0000000000000000000000000000000000000000..0855aaaa0e0b2e26af70e2d26f273bc88797b15a
Binary files /dev/null and b/controls/model/SFB__actuation_mat__SFB.mat differ
diff --git a/controls/model/Testing/Actuation_Tests/ESC_Test.m b/controls/model/Testing/Actuation_Tests/ESC_Test.m
new file mode 100644
index 0000000000000000000000000000000000000000..83df53c107bff1c6edfa2f16d6990e832ece26b7
--- /dev/null
+++ b/controls/model/Testing/Actuation_Tests/ESC_Test.m
@@ -0,0 +1,8 @@
+%Test Script for the ESC in Actuation
+%Created by Gautham Ajith
+
+clf("reset");
+
+P = [0.1, 0.1, 0.1, 2];
+
+ESC_Block = ESC_System(P);
diff --git a/controls/model/Testing/drone_control_system_test.m b/controls/model/Testing/drone_control_system_test.m
new file mode 100644
index 0000000000000000000000000000000000000000..57a602a67499a3f6eea8d4de520676b469dfe099
--- /dev/null
+++ b/controls/model/Testing/drone_control_system_test.m
@@ -0,0 +1,131 @@
+% A test script intended to demo the functionality of DroneControlSystem.m
+% I don't have a good drone plant model yet so all this does is check to
+% see if everything compiles correctly.
+%
+%
+% Author: Austin Beinder
+%
+
+% ------------------------------------------------------------------------
+z_controller = PIminusDController(-0.098040, -0.00817, -0.07353, 0.1); % currently not using alpha
+z_max = 20000;
+z_min = -20000;
+
+y_pid = PIminusDController(0.55, 0.0075, 0, 0.1);
+y_pid1 = PIminusDController(0, 0, -1, 0.1);
+y_vel_pid = PIminusDController(0.1, 0, 0.02, 0.1);
+roll_pid = PIminusDController(35, 0, 1, 0.1);
+roll_rate_pid = PIminusDController(0.03, 0, 0.005, 0.1);
+
+y_max = 20000;
+y_min = -20000;
+
+x_pid = PIminusDController(0.55, 0.0075, 0, 0.1);
+y_pid2 = PIminusDController(0, 0, -1, 0.1);
+x_vel_pid = PIminusDController(-0.1, 0, -0.02, 0.1);
+pitch_pid = PIminusDController(35, 0, 1, 0.1);
+pitch_rate_pid = PIminusDController(0.03, 0, 0.005, 0.1);
+
+x_max = 20000;
+x_min = -20000;
+
+yaw_pid = PIminusDController(2.6, 0, 0, 0.1);
+yaw_rate_pid = PIminusDController(0.297, 0, 0, 0.1);
+
+yaw_max = 20000;
+yaw_min = -20000;
+
+drone_controller = DronePIDController(z_controller, z_max, z_min, y_pid, y_pid1, y_vel_pid, roll_pid, roll_rate_pid, y_max, y_min, ...
+                x_pid, y_pid2, x_vel_pid, pitch_pid, pitch_rate_pid, x_max, x_min, yaw_pid, yaw_rate_pid, yaw_max, yaw_min);
+
+% -------------------------------------------------------------------------
+% Model Parameters
+    m = 1.216;                          % Quadrotor + battery mass
+    g = 9.81;                           % Acceleration of gravity
+    Jxx = 0.0110;%0.0130;               % Quadrotor and battery motor of inertia around bx (pitch)
+    Jyy = 0.0116;%0.0140;               % Quadrotor and battery motor of inertia around by (roll)
+    Jzz = 0.0223;%0.0285;               % Quadrotor and battery motor of inertia around bz (yaw)
+    J = diag([ Jxx Jyy Jzz ]);
+    Jreq = 4.2012e-05;                  % Rotor and motor moment of inertia around axis of rotation 
+    Kt = 1.2007e-05;                    % Rotor thrust constant
+    delta_T = [ 0,  0,  9.404e-04 ];    % Thrust constant adjustment factor
+    Kh = 3.4574e-04;                    % Rotor in-plane drag constant
+    Kd = 1.4852e-07;                    % Rotor drag constant
+    rhx = 0.16;                         % X-axis distance from center of mass to a rotor hub
+    rhy = 0.16;                         % Y-axis distance from center of mass to a rotor hub
+    rhz = 0.03;                         % 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.235;                         % Motor resistance
+    Kq = 96.3422;                       % Motor torque constant
+    Kv = 96.3422;                       % Motor back emf constant
+    If = 0.3836;                        % 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 = 12.3;                          % Nominal battery voltage (V)
+
+
+% 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);
+
+% -------------------------------------------------------------------------
+
+controller = DroneControlSystem(drone_controller, signal_mixer, 1, 0, lqr_K);
+
+% -------------------------------------------------------------------------
+err = 0;
+desired = 10;
+value = 0;
+value2 = 0;
+value3 = 0;
+
+y_setpoint = 0; 
+y_position = 0;  
+roll = 0; 
+roll_rate = 0; 
+x_setpoint  = 0; 
+x_position  = 0; 
+pitch = 0; 
+pitch_rate = 0; 
+yaw_setpoint  = 0; 
+yaw = 0; 
+yaw_rate = 0; 
+
+arr = zeros(100);
+arr2 = zeros(100);
+arr3 = zeros(100);
+delta_t = 0.2;
+
+euler_angles_filtered = zeros(1,3);
+euler_rates = zeros(1,3);
+current_position = [0, 0, 0];
+velocity = zeros(1,3);
+throttle_command = 0; 
+y_controlled = 0;
+x_controlled = 0;
+yaw_controlled = 0; 
+lqr_switch = 1;
+setpoints = [0, 0, 0, 0];
+delta_t = 1;
+
+
+for a = 1:100
+    % todo honestly you need something to pretend to be a drone here
+    [P, setpoint_error, controller] = controller.nextOutput(setpoints, euler_angles_filtered, euler_rates, current_position, velocity, throttle_command, y_controlled, x_controlled, yaw_controlled, lqr_switch, delta_t);
+end
+
+
diff --git a/controls/model/Testing/drone_gamepad_test.m b/controls/model/Testing/drone_gamepad_test.m
new file mode 100644
index 0000000000000000000000000000000000000000..6096a2e7013b7edd7f4f39c90c276b12abfd5812
--- /dev/null
+++ b/controls/model/Testing/drone_gamepad_test.m
@@ -0,0 +1,47 @@
+% This script offers a demo of how to use the drone_gamepad_input 
+% function and plots the yaw, elevation, x and y position.
+% Essentially, it just integrates the x and y joystick positions.
+% Intended for the Logitech F310 controllers found in the MicroCart and
+% 476 room.
+
+e = 0;
+yaw = 0;
+xa = 0;
+y = 0;
+gamepad = vrjoystick(1);
+
+
+T = 500;
+passo = 1;
+t=1;
+x1=0;
+x2=0;
+x3=0;
+x4=0;
+while 1
+
+    position = drone_gamepad_input(yaw, e, y, xa, gamepad);
+
+    yaw = position(1)
+    e = position(2)
+    y = position(3)
+    xa = position(4)
+
+    x1=[x1,yaw];
+    plot(x1);
+    hold on
+    x2=[x2,e];
+    plot(x2);
+    x3=[x3,y];
+    plot(x3);
+    x4=[x4,xa];
+    plot(x4);
+    hold off
+    
+    %pay attention to this command %
+    axis([T*fix(t/T),T+T*fix(t/T),-15,15]); 
+    grid
+    t=t+passo;
+    drawnow;
+    tic(); pause(0.1); toc()
+end
\ No newline at end of file
diff --git a/controls/model/Testing/drone_pid_test.m b/controls/model/Testing/drone_pid_test.m
new file mode 100644
index 0000000000000000000000000000000000000000..b4efbcbed0ad7a387203fd78be927ab516c01614
--- /dev/null
+++ b/controls/model/Testing/drone_pid_test.m
@@ -0,0 +1,80 @@
+% A test script intended to demo the functionality of DronePIDController.m
+%
+% Author: Austin Beinder
+%
+
+z_controller = PIminusDController(-0.098040, -0.00817, -0.07353, 0.1); % currently not using alpha
+z_max = 20000;
+z_min = -20000;
+
+y_pid = PIminusDController(0.55, 0.0075, 0, 0.1);
+y_pid1 = PIminusDController(0, 0, -1, 0.1);
+y_vel_pid = PIminusDController(0.1, 0, 0.02, 0.1);
+roll_pid = PIminusDController(35, 0, 1, 0.1);
+roll_rate_pid = PIminusDController(0.03, 0, 0.005, 0.1);
+
+y_max = 20000;
+y_min = -20000;
+
+x_pid = PIminusDController(0.55, 0.0075, 0, 0.1);
+y_pid2 = PIminusDController(0, 0, -1, 0.1);
+x_vel_pid = PIminusDController(-0.1, 0, -0.02, 0.1);
+pitch_pid = PIminusDController(35, 0, 1, 0.1);
+pitch_rate_pid = PIminusDController(0.03, 0, 0.005, 0.1);
+
+x_max = 20000;
+x_min = -20000;
+
+yaw_pid = PIminusDController(2.6, 0, 0, 0.1);
+yaw_rate_pid = PIminusDController(0.297, 0, 0, 0.1);
+
+yaw_max = 20000;
+yaw_min = -20000;
+
+drone_controller = DronePIDController(z_controller, z_max, z_min, y_pid, y_pid1, y_vel_pid, roll_pid, roll_rate_pid, y_max, y_min, ...
+                x_pid, y_pid2, x_vel_pid, pitch_pid, pitch_rate_pid, x_max, x_min, yaw_pid, yaw_rate_pid, yaw_max, yaw_min);
+           
+err = 0;
+desired = 10;
+value = 0;
+value2 = 0;
+value3 = 0;
+
+y_setpoint = 0; 
+y_position = 0;  
+roll = 0; 
+roll_rate = 0; 
+x_setpoint  = 0; 
+x_position  = 0; 
+pitch = 0; 
+pitch_rate = 0; 
+yaw_setpoint  = 0; 
+yaw = 0; 
+yaw_rate = 0; 
+
+arr = zeros(100);
+arr2 = zeros(100);
+arr3 = zeros(100);
+delta_t = 0.2;
+
+for a = 1:100
+    err = desired - value;
+    value3 = value2;
+    [value2, y_controlled, x_controlled, yaw_controlled, drone_controller] = drone_controller.nextOutput(desired, value, ...
+        y_setpoint, y_position, roll, roll_rate, ...
+                x_setpoint, x_position, pitch, pitch_rate, yaw_setpoint, yaw, yaw_rate, delta_t);
+
+    value = value + value2*delta_t;
+    
+    arr(a) = value;
+    arr2(a) = err;
+    arr3(a) = value2;
+end
+
+plot(arr)
+hold on
+plot(arr2)
+%plot(arr3)
+hold off
+
+legend('output', 'error')
diff --git a/controls/model/Testing/imu_model_test.m b/controls/model/Testing/imu_model_test.m
new file mode 100644
index 0000000000000000000000000000000000000000..e79729bfa444d7c0ccdfbd81faa1fd6da027a7a6
--- /dev/null
+++ b/controls/model/Testing/imu_model_test.m
@@ -0,0 +1,46 @@
+% A test script intended to demo the functionality of RealTimePIDController.m
+%
+% Author: Austin Beinder
+%
+
+clf("reset");
+accelerometer_sample_time = 0.1
+accelerometer_transfer_function = 0;
+accelerometer_noise = [0.01, 0.01, 0.01];
+gyroscope_sample_time = 0.1;
+gyroscope_noise = [0.01, 0.01, 0.01];
+gyroscope_transfer_function = 0;
+imu_model = IMUModel(accelerometer_sample_time, ...
+                accelerometer_transfer_function, ...
+                accelerometer_noise, ...
+                gyroscope_sample_time, ...
+                gyroscope_noise, ...
+                gyroscope_transfer_function);
+
+B_vo_dot = 0.1;
+B_vo = [0.1, 0.1, 0.1];
+B_Omega = [0.1, 0.1, 0.1];
+B_g = 0.1;
+g = 0.1;
+r_oc = 0.1;
+
+arr = zeros(3, 1000);
+arr2 = zeros(3, 1000);
+arr3 = zeros(3, 1000);
+delta_t = 0.1;
+
+for a = 1:1000
+    [value, value2, pid1] = imu_model.nextOutput(B_vo_dot, B_vo, B_Omega, B_g, g, r_oc, delta_t);
+
+    arr(:,a) = value;
+    arr3(:,a) = value2;
+
+end
+
+plot(arr(1,1,:))
+hold on
+plot(arr2(1,1,:))
+plot(arr3(1,1,:))
+hold off
+
+legend('actuator','error', 'output')
diff --git a/controls/model/Testing/pi_minus_d_test.m b/controls/model/Testing/pi_minus_d_test.m
new file mode 100644
index 0000000000000000000000000000000000000000..4f9d37b5bb178d20a974ccef944958ac3e968137
--- /dev/null
+++ b/controls/model/Testing/pi_minus_d_test.m
@@ -0,0 +1,39 @@
+% A test script intended to demo the functionality of PIminusDController.m
+%
+% Author: Austin Beinder
+%
+
+
+piminusd = PIminusDController(2, 0.5, 0.1, 0.1);
+%pi_c = pid(1, 1, 0, 0, 0.1)
+
+err = 10;
+desired = 10;
+value = 3;
+value2 = 0;
+value3 = 0;
+
+arr = zeros(100);
+arr2 = zeros(100);
+arr3 = zeros(100);
+delta_t = 0.2;
+
+for a = 1:100
+    err = desired - value;
+
+    [value2, piminusd] = piminusd.pi_minus_d(err, value, delta_t);
+
+    value = value + value2*delta_t;
+    
+    arr(a) = value2;
+    arr2(a) = err;
+    arr3(a) = value;
+end
+
+plot(arr)
+hold on
+plot(arr2)
+plot(arr3)
+hold off
+
+legend('actuator','error', 'output')
diff --git a/controls/model/Testing/real_time_d_test.m b/controls/model/Testing/real_time_d_test.m
new file mode 100644
index 0000000000000000000000000000000000000000..1c8b5f47f1f285367a4befc4f5747a06cf251dfb
--- /dev/null
+++ b/controls/model/Testing/real_time_d_test.m
@@ -0,0 +1,38 @@
+% A test script intended to demo the functionality of RealTimeDerivativeController.m
+%
+% Author: Austin Beinder
+%
+
+
+clf("reset");
+
+pid1 = RealTimeDerivativeController(0.1);
+
+err = 10;
+desired = 10;
+value = 3;
+value2 = 0;
+
+arr = zeros(100);
+arr2 = zeros(100);
+arr3 = zeros(100);
+delta_t = 0.01;
+
+for a = 1:100
+    err = desired - value2;
+    [value, pid1] = pid1.nextOutput(err, delta_t);
+    value2 = value2 + value*delta_t;
+
+    arr(a) = value;
+    arr2(a) = err;
+    arr3(a) = value2;
+
+end
+
+plot(arr)
+hold on
+plot(arr2)
+plot(arr3)
+hold off
+
+legend('actuator','error', 'output')
diff --git a/controls/model/Testing/real_time_pid_test.m b/controls/model/Testing/real_time_pid_test.m
new file mode 100644
index 0000000000000000000000000000000000000000..461adf16d4689f75f372b22d86ecfeb3658b83bb
--- /dev/null
+++ b/controls/model/Testing/real_time_pid_test.m
@@ -0,0 +1,38 @@
+% A test script intended to demo the functionality of RealTimePIDController.m
+%
+% Author: Austin Beinder
+%
+
+clf("reset");
+
+pid1 = RealTimePIDController(0.1, 0.1, 0.01);
+%pi_c = pid(1, 1, 0, 0, 0.1)
+
+err = 10;
+desired = 10;
+value = 3;
+value2 = 0;
+
+arr = zeros(1000);
+arr2 = zeros(1000);
+arr3 = zeros(1000);
+delta_t = 0.1;
+
+for a = 1:1000
+    err = desired - value2;
+    [value, pid1] = pid1.nextOutput(err, delta_t);
+    value2 = value2 + value*delta_t;
+
+    arr(a) = value;
+    arr2(a) = err;
+    arr3(a) = value2;
+
+end
+
+plot(arr)
+hold on
+plot(arr2)
+plot(arr3)
+hold off
+
+legend('actuator','error', 'output')
diff --git a/controls/model/Testing/test_drone_gamepad_input.asv b/controls/model/Testing/test_drone_gamepad_input.asv
new file mode 100644
index 0000000000000000000000000000000000000000..7dc0a55b9b37ceb8d526b6c1d27ad932feb9450c
--- /dev/null
+++ b/controls/model/Testing/test_drone_gamepad_input.asv
@@ -0,0 +1,37 @@
+
+e = 0;
+yaw = 0;
+x = 0;
+y = 0;
+gamepad = vrjoystick(1);
+
+while 1
+
+    
+
+end
+
+T = 500;
+passo = 1;
+t=1;
+x=0;
+while 1
+
+    position = drone_gamepad_input(y, e, y, x, gamepad);
+
+    yaw = position(1)
+    e = position(2)
+    y = position(3)
+    x = position(4)
+
+    b=
+    x=[x,b];
+    plot(x);
+    hold on
+
+    %pay attention to this command %
+    axis([T*fix(t/T),T+T*fix(t/T),0,1024]); 
+    grid
+    t=t+passo;
+    drawnow;
+end
\ No newline at end of file
diff --git a/controls/model/actuation_mat.c b/controls/model/actuation_mat.c
new file mode 100644
index 0000000000000000000000000000000000000000..580989ad10b6f43ed2b04e422a4d7383c0fcabb9
--- /dev/null
+++ b/controls/model/actuation_mat.c
@@ -0,0 +1,372 @@
+/*
+ * File: actuation_mat.c
+ *
+ *
+ *   --- THIS FILE GENERATED BY S-FUNCTION BUILDER: 3.0 ---
+ *
+ *   This file is an S-function produced by the S-Function
+ *   Builder which only recognizes certain fields.  Changes made
+ *   outside these fields will be lost the next time the block is
+ *   used to load, edit, and resave this file. This file will be overwritten
+ *   by the S-function Builder block. If you want to edit this file by hand,
+ *   you must change it only in the area defined as:
+ *
+ *        %%%-SFUNWIZ_defines_Changes_BEGIN
+ *        #define NAME 'replacement text'
+ *        %%% SFUNWIZ_defines_Changes_END
+ *
+ *   DO NOT change NAME--Change the 'replacement text' only.
+ *
+ *   For better compatibility with the Simulink Coder, the
+ *   "wrapper" S-function technique is used.  This is discussed
+ *   in the Simulink Coder's Manual in the Chapter titled,
+ *   "Wrapper S-functions".
+ *
+ *  -------------------------------------------------------------------------
+ * | See matlabroot/simulink/src/sfuntmpl_doc.c for a more detailed template |
+ *  -------------------------------------------------------------------------
+ *
+ * Created: Mon Oct 31 17:30:02 2022
+ */
+
+#define S_FUNCTION_LEVEL               2
+#define S_FUNCTION_NAME                actuation_mat
+
+/*<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<*/
+/* %%%-SFUNWIZ_defines_Changes_BEGIN --- EDIT HERE TO _END */
+#define NUM_INPUTS                     1
+
+/* Input Port  0 */
+#define IN_PORT_0_NAME                 P
+#define INPUT_0_DIMS_ND                {1,1}
+#define INPUT_0_NUM_ELEMS              1
+#define INPUT_0_WIDTH                  1
+#define INPUT_DIMS_0_COL               1
+#define INPUT_0_DTYPE                  real_T
+#define INPUT_0_COMPLEX                COMPLEX_NO
+#define IN_0_BUS_BASED                 0
+#define IN_0_BUS_NAME
+#define IN_0_DIMS                      1-D
+#define INPUT_0_FEEDTHROUGH            1
+#define IN_0_ISSIGNED                  0
+#define IN_0_WORDLENGTH                8
+#define IN_0_FIXPOINTSCALING           1
+#define IN_0_FRACTIONLENGTH            9
+#define IN_0_BIAS                      0
+#define IN_0_SLOPE                     0.125
+#define NUM_OUTPUTS                    6
+
+/* Output Port  0 */
+#define OUT_PORT_0_NAME                B_omega
+#define OUTPUT_0_DIMS_ND               {1,1}
+#define OUTPUT_0_NUM_ELEMS             1
+#define OUTPUT_0_WIDTH                 1
+#define OUTPUT_DIMS_0_COL              1
+#define OUTPUT_0_DTYPE                 real_T
+#define OUTPUT_0_COMPLEX               COMPLEX_NO
+#define OUT_0_BUS_BASED                0
+#define OUT_0_BUS_NAME
+#define OUT_0_DIMS                     1-D
+#define OUT_0_ISSIGNED                 1
+#define OUT_0_WORDLENGTH               8
+#define OUT_0_FIXPOINTSCALING          1
+#define OUT_0_FRACTIONLENGTH           3
+#define OUT_0_BIAS                     0
+#define OUT_0_SLOPE                    0.125
+
+/* Output Port  1 */
+#define OUT_PORT_1_NAME                euler_angles
+#define OUTPUT_1_DIMS_ND               {1,1}
+#define OUTPUT_1_NUM_ELEMS             1
+#define OUTPUT_1_WIDTH                 1
+#define OUTPUT_DIMS_1_COL              1
+#define OUTPUT_1_DTYPE                 real_T
+#define OUTPUT_1_COMPLEX               COMPLEX_NO
+#define OUT_1_BUS_BASED                0
+#define OUT_1_BUS_NAME
+#define OUT_1_DIMS                     1-D
+#define OUT_1_ISSIGNED                 1
+#define OUT_1_WORDLENGTH               8
+#define OUT_1_FIXPOINTSCALING          1
+#define OUT_1_FRACTIONLENGTH           3
+#define OUT_1_BIAS                     0
+#define OUT_1_SLOPE                    0.125
+
+/* Output Port  2 */
+#define OUT_PORT_2_NAME                B_vo
+#define OUTPUT_2_DIMS_ND               {1,1}
+#define OUTPUT_2_NUM_ELEMS             1
+#define OUTPUT_2_WIDTH                 1
+#define OUTPUT_DIMS_2_COL              1
+#define OUTPUT_2_DTYPE                 real_T
+#define OUTPUT_2_COMPLEX               COMPLEX_NO
+#define OUT_2_BUS_BASED                0
+#define OUT_2_BUS_NAME
+#define OUT_2_DIMS                     1-D
+#define OUT_2_ISSIGNED                 1
+#define OUT_2_WORDLENGTH               8
+#define OUT_2_FIXPOINTSCALING          1
+#define OUT_2_FRACTIONLENGTH           3
+#define OUT_2_BIAS                     0
+#define OUT_2_SLOPE                    0.125
+
+/* Output Port  3 */
+#define OUT_PORT_3_NAME                E_ro
+#define OUTPUT_3_DIMS_ND               {1,1}
+#define OUTPUT_3_NUM_ELEMS             1
+#define OUTPUT_3_WIDTH                 1
+#define OUTPUT_DIMS_3_COL              1
+#define OUTPUT_3_DTYPE                 real_T
+#define OUTPUT_3_COMPLEX               COMPLEX_NO
+#define OUT_3_BUS_BASED                0
+#define OUT_3_BUS_NAME
+#define OUT_3_DIMS                     1-D
+#define OUT_3_ISSIGNED                 1
+#define OUT_3_WORDLENGTH               8
+#define OUT_3_FIXPOINTSCALING          1
+#define OUT_3_FRACTIONLENGTH           3
+#define OUT_3_BIAS                     0
+#define OUT_3_SLOPE                    0.125
+
+/* Output Port  4 */
+#define OUT_PORT_4_NAME                B_vo_dot
+#define OUTPUT_4_DIMS_ND               {1,1}
+#define OUTPUT_4_NUM_ELEMS             1
+#define OUTPUT_4_WIDTH                 1
+#define OUTPUT_DIMS_4_COL              1
+#define OUTPUT_4_DTYPE                 real_T
+#define OUTPUT_4_COMPLEX               COMPLEX_NO
+#define OUT_4_BUS_BASED                0
+#define OUT_4_BUS_NAME
+#define OUT_4_DIMS                     1-D
+#define OUT_4_ISSIGNED                 1
+#define OUT_4_WORDLENGTH               8
+#define OUT_4_FIXPOINTSCALING          1
+#define OUT_4_FRACTIONLENGTH           3
+#define OUT_4_BIAS                     0
+#define OUT_4_SLOPE                    0.125
+
+/* Output Port  5 */
+#define OUT_PORT_5_NAME                B_g
+#define OUTPUT_5_DIMS_ND               {1,1}
+#define OUTPUT_5_NUM_ELEMS             1
+#define OUTPUT_5_WIDTH                 1
+#define OUTPUT_DIMS_5_COL              1
+#define OUTPUT_5_DTYPE                 real_T
+#define OUTPUT_5_COMPLEX               COMPLEX_NO
+#define OUT_5_BUS_BASED                0
+#define OUT_5_BUS_NAME
+#define OUT_5_DIMS                     1-D
+#define OUT_5_ISSIGNED                 1
+#define OUT_5_WORDLENGTH               8
+#define OUT_5_FIXPOINTSCALING          1
+#define OUT_5_FRACTIONLENGTH           3
+#define OUT_5_BIAS                     0
+#define OUT_5_SLOPE                    0.125
+#define NPARAMS                        0
+#define SAMPLE_TIME_0                  INHERITED_SAMPLE_TIME
+#define NUM_DISC_STATES                0
+#define DISC_STATES_IC                 [0]
+#define NUM_CONT_STATES                0
+#define CONT_STATES_IC                 [0]
+#define SFUNWIZ_GENERATE_TLC           1
+#define SOURCEFILES                    "__SFB__"
+#define PANELINDEX                     N/A
+#define USE_SIMSTRUCT                  0
+#define SHOW_COMPILE_STEPS             0
+#define CREATE_DEBUG_MEXFILE           0
+#define SAVE_CODE_ONLY                 1
+#define SFUNWIZ_REVISION               3.0
+
+/* %%%-SFUNWIZ_defines_Changes_END --- EDIT HERE TO _BEGIN */
+/*<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<*/
+#include "simstruc.h"
+
+extern void actuation_mat_Outputs_wrapper(const real_T *P,
+  real_T *B_omega,
+  real_T *euler_angles,
+  real_T *B_vo,
+  real_T *E_ro,
+  real_T *B_vo_dot,
+  real_T *B_g);
+
+/*====================*
+ * S-function methods *
+ *====================*/
+/* Function: mdlInitializeSizes ===============================================
+ * Abstract:
+ *   Setup sizes of the various vectors.
+ */
+static void mdlInitializeSizes(SimStruct *S)
+{
+  DECL_AND_INIT_DIMSINFO(inputDimsInfo);
+  DECL_AND_INIT_DIMSINFO(outputDimsInfo);
+  ssSetNumSFcnParams(S, NPARAMS);
+  if (ssGetNumSFcnParams(S) != ssGetSFcnParamsCount(S)) {
+    return;                            /* Parameter mismatch will be reported by Simulink */
+  }
+
+  ssSetArrayLayoutForCodeGen(S, SS_COLUMN_MAJOR);
+  ssSetOperatingPointCompliance(S, USE_DEFAULT_OPERATING_POINT);
+  ssSetNumContStates(S, NUM_CONT_STATES);
+  ssSetNumDiscStates(S, NUM_DISC_STATES);
+  if (!ssSetNumInputPorts(S, NUM_INPUTS))
+    return;
+
+  /* Input Port 0 */
+  ssSetInputPortWidth(S, 0, INPUT_0_NUM_ELEMS);
+  ssSetInputPortDataType(S, 0, SS_DOUBLE);
+  ssSetInputPortComplexSignal(S, 0, INPUT_0_COMPLEX);
+  ssSetInputPortDirectFeedThrough(S, 0, INPUT_0_FEEDTHROUGH);
+  ssSetInputPortRequiredContiguous(S, 0, 1);/*direct input signal access*/
+  if (!ssSetNumOutputPorts(S, NUM_OUTPUTS))
+    return;
+
+  /* Output Port 0 */
+  ssSetOutputPortWidth(S, 0, OUTPUT_0_NUM_ELEMS);
+  ssSetOutputPortDataType(S, 0, SS_DOUBLE);
+  ssSetOutputPortComplexSignal(S, 0, OUTPUT_0_COMPLEX);
+
+  /* Output Port 1 */
+  ssSetOutputPortWidth(S, 1, OUTPUT_1_NUM_ELEMS);
+  ssSetOutputPortDataType(S, 1, SS_DOUBLE);
+  ssSetOutputPortComplexSignal(S, 1, OUTPUT_1_COMPLEX);
+
+  /* Output Port 2 */
+  ssSetOutputPortWidth(S, 2, OUTPUT_2_NUM_ELEMS);
+  ssSetOutputPortDataType(S, 2, SS_DOUBLE);
+  ssSetOutputPortComplexSignal(S, 2, OUTPUT_2_COMPLEX);
+
+  /* Output Port 3 */
+  ssSetOutputPortWidth(S, 3, OUTPUT_3_NUM_ELEMS);
+  ssSetOutputPortDataType(S, 3, SS_DOUBLE);
+  ssSetOutputPortComplexSignal(S, 3, OUTPUT_3_COMPLEX);
+
+  /* Output Port 4 */
+  ssSetOutputPortWidth(S, 4, OUTPUT_4_NUM_ELEMS);
+  ssSetOutputPortDataType(S, 4, SS_DOUBLE);
+  ssSetOutputPortComplexSignal(S, 4, OUTPUT_4_COMPLEX);
+
+  /* Output Port 5 */
+  ssSetOutputPortWidth(S, 5, OUTPUT_5_NUM_ELEMS);
+  ssSetOutputPortDataType(S, 5, SS_DOUBLE);
+  ssSetOutputPortComplexSignal(S, 5, OUTPUT_5_COMPLEX);
+  ssSetNumPWork(S, 0);
+  ssSetNumSampleTimes(S, 1);
+  ssSetNumRWork(S, 0);
+  ssSetNumIWork(S, 0);
+  ssSetNumModes(S, 0);
+  ssSetNumNonsampledZCs(S, 0);
+  ssSetSimulinkVersionGeneratedIn(S, "10.6");
+
+  /* Take care when specifying exception free code - see sfuntmpl_doc.c */
+  ssSetOptions(S, (SS_OPTION_EXCEPTION_FREE_CODE |
+                   SS_OPTION_USE_TLC_WITH_ACCELERATOR |
+                   SS_OPTION_WORKS_WITH_CODE_REUSE));
+}
+
+#if defined(MATLAB_MEX_FILE)
+#define MDL_SET_INPUT_PORT_DIMENSION_INFO
+
+static void mdlSetInputPortDimensionInfo(SimStruct *S,
+  int_T port,
+  const DimsInfo_T *dimsInfo)
+{
+  if (!ssSetInputPortDimensionInfo(S, port, dimsInfo))
+    return;
+}
+
+#endif
+
+#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO
+#if defined(MDL_SET_OUTPUT_PORT_DIMENSION_INFO)
+
+static void mdlSetOutputPortDimensionInfo(SimStruct *S,
+  int_T port,
+  const DimsInfo_T *dimsInfo)
+{
+  if (!ssSetOutputPortDimensionInfo(S, port, dimsInfo))
+    return;
+}
+
+#endif
+
+/* Function: mdlInitializeSampleTimes =========================================
+ * Abstract:
+ *    Specifiy  the sample time.
+ */
+static void mdlInitializeSampleTimes(SimStruct *S)
+{
+  ssSetSampleTime(S, 0, SAMPLE_TIME_0);
+  ssSetModelReferenceSampleTimeDefaultInheritance(S);
+  ssSetOffsetTime(S, 0, 0.0);
+}
+
+#define MDL_SET_INPUT_PORT_DATA_TYPE
+
+static void mdlSetInputPortDataType(SimStruct *S, int port, DTypeId dType)
+{
+  ssSetInputPortDataType(S, 0, dType);
+}
+
+#define MDL_SET_OUTPUT_PORT_DATA_TYPE
+
+static void mdlSetOutputPortDataType(SimStruct *S, int port, DTypeId dType)
+{
+  ssSetOutputPortDataType(S, 0, dType);
+}
+
+#define MDL_SET_DEFAULT_PORT_DATA_TYPES
+
+static void mdlSetDefaultPortDataTypes(SimStruct *S)
+{
+  ssSetInputPortDataType(S, 0, SS_DOUBLE);
+  ssSetOutputPortDataType(S, 0, SS_DOUBLE);
+}
+
+#define MDL_START                                                /* Change to #undef to remove function */
+#if defined(MDL_START)
+
+/* Function: mdlStart =======================================================
+ * Abstract:
+ *    This function is called once at start of model execution. If you
+ *    have states that should be initialized once, this is the place
+ *    to do it.
+ */
+static void mdlStart(SimStruct *S)
+{
+}
+
+#endif                                 /*  MDL_START */
+
+/* Function: mdlOutputs =======================================================
+ *
+ */
+static void mdlOutputs(SimStruct *S, int_T tid)
+{
+  const real_T *P = (real_T *) ssGetInputPortRealSignal(S, 0);
+  real_T *B_omega = (real_T *) ssGetOutputPortRealSignal(S, 0);
+  real_T *euler_angles = (real_T *) ssGetOutputPortRealSignal(S, 1);
+  real_T *B_vo = (real_T *) ssGetOutputPortRealSignal(S, 2);
+  real_T *E_ro = (real_T *) ssGetOutputPortRealSignal(S, 3);
+  real_T *B_vo_dot = (real_T *) ssGetOutputPortRealSignal(S, 4);
+  real_T *B_g = (real_T *) ssGetOutputPortRealSignal(S, 5);
+  actuation_mat_Outputs_wrapper(P, B_omega, euler_angles, B_vo, E_ro, B_vo_dot,
+    B_g);
+}
+
+/* Function: mdlTerminate =====================================================
+ * Abstract:
+ *    In this function, you should perform any actions that are necessary
+ *    at the termination of a simulation.  For example, if memory was
+ *    allocated in mdlStart, this is the place to free it.
+ */
+static void mdlTerminate(SimStruct *S)
+{
+}
+
+#ifdef MATLAB_MEX_FILE                 /* Is this file being compiled as a MEX-file? */
+#include "simulink.c"                  /* MEX-file interface mechanism */
+#else
+#include "cg_sfun.h"                   /* Code generation registration function */
+#endif
diff --git a/controls/model/actuation_mat.tlc b/controls/model/actuation_mat.tlc
new file mode 100644
index 0000000000000000000000000000000000000000..854e66fe37d763f508130e93ad2ea855617bb77f
--- /dev/null
+++ b/controls/model/actuation_mat.tlc
@@ -0,0 +1,153 @@
+%% File : actuation_mat.tlc
+%% Created : Mon Oct 31 17:30:02 2022
+%%
+%% Description: 
+%%   Simulink Coder wrapper functions interface generated for 
+%%   S-function "actuation_mat.c".
+%%
+%%         File generated by S-function Builder Block
+%%
+%%   For more information on using the Target Language with the 
+%%   Simulink Coder, see the Target Language Compiler manual
+%%   (under Simulink Coder) in the "Inlining S-Functions"
+%%   chapter under the section and subsection:
+%%     "Writing Block Target Files to Inline S-Functions",
+%%        "Function-Based or Wrappered Code".
+%%
+%implements  actuation_mat "C"
+%% Function: BlockTypeSetup ===================================================
+%%
+%% Purpose:
+%%      Set up external references for wrapper functions in the 
+%%      generated code.
+%%
+%function BlockTypeSetup(block, system) Output
+    %assign realType = LibGetDataTypeNameFromId(::CompiledModel.tSS_DOUBLE)
+
+  %if IsModelReferenceSimTarget() || CodeFormat == "S-Function" || ::isRAccel
+    %assign hFileName = "actuation_mat_accel_wrapper"
+    %assign hFileNameMacro = FEVAL("upper", hFileName)
+    %openfile hFile = "%<hFileName>.h"
+    %selectfile hFile
+    #ifndef _%<hFileNameMacro>_H_
+    #define _%<hFileNameMacro>_H_
+
+    #ifdef MATLAB_MEX_FILE
+    #include "tmwtypes.h"
+    #else
+    #include "rtwtypes.h"
+    #endif
+    #ifdef __cplusplus
+    #define SFB_EXTERN_C extern "C"
+    #else
+    #define SFB_EXTERN_C extern
+    #endif
+    SFB_EXTERN_C void actuation_mat_Outputs_wrapper_accel(const %<realType> *P,
+			%<realType> *B_omega,
+			%<realType> *euler_angles,
+			%<realType> *B_vo,
+			%<realType> *E_ro,
+			%<realType> *B_vo_dot,
+			%<realType> *B_g);
+    #undef SFB_EXTERN_C
+    #endif
+    %closefile hFile
+
+    %assign cFileName = "actuation_mat_accel_wrapper"
+    %openfile cFile = "%<cFileName>.c"
+    %selectfile cFile
+    #include <string.h>
+    #ifdef MATLAB_MEX_FILE
+    #include "tmwtypes.h"
+    #else
+    #include "rtwtypes.h"
+    #endif
+    #include "%<hFileName>.h"
+    
+
+    extern void actuation_mat_Start_wrapper(void);
+    extern void actuation_mat_Outputs_wrapper(const %<realType> *P,
+			%<realType> *B_omega,
+			%<realType> *euler_angles,
+			%<realType> *B_vo,
+			%<realType> *E_ro,
+			%<realType> *B_vo_dot,
+			%<realType> *B_g);
+    extern void actuation_mat_Terminate_wrapper(void);
+    void actuation_mat_Outputs_wrapper_accel(const %<realType> *P,
+			%<realType> *B_omega,
+			%<realType> *euler_angles,
+			%<realType> *B_vo,
+			%<realType> *E_ro,
+			%<realType> *B_vo_dot,
+			%<realType> *B_g){
+    actuation_mat_Outputs_wrapper(P,
+			B_omega,
+			euler_angles,
+			B_vo,
+			E_ro,
+			B_vo_dot,
+			B_g);
+    }
+
+    %closefile cFile
+
+    %<LibAddToCommonIncludes("%<hFileName>.h")>
+
+  %else
+  %openfile externs
+
+    #ifdef __cplusplus
+    #define SFB_EXTERN_C extern "C"
+    #else
+    #define SFB_EXTERN_C extern
+    #endif
+
+    SFB_EXTERN_C void actuation_mat_Start_wrapper(void);
+
+    SFB_EXTERN_C void actuation_mat_Outputs_wrapper(const %<realType> *P,
+			%<realType> *B_omega,
+			%<realType> *euler_angles,
+			%<realType> *B_vo,
+			%<realType> *E_ro,
+			%<realType> *B_vo_dot,
+			%<realType> *B_g);
+
+    SFB_EXTERN_C void actuation_mat_Terminate_wrapper(void);
+
+    #undef SFB_EXTERN_C
+  %closefile externs
+  %<LibCacheExtern(externs)>
+
+  %endif
+  %%
+%endfunction
+
+
+%% Function: Outputs ==========================================================
+%%
+%% Purpose:
+%%      Code generation rules for mdlOutputs function.
+%%
+%function Outputs(block, system) Output
+  %%
+  %assign pu0 = LibBlockInputSignalAddr(0, "", "", 0)
+  %assign py0 = LibBlockOutputSignalAddr(0, "", "", 0)
+  %assign py1 = LibBlockOutputSignalAddr(1, "", "", 0)
+  %assign py2 = LibBlockOutputSignalAddr(2, "", "", 0)
+  %assign py3 = LibBlockOutputSignalAddr(3, "", "", 0)
+  %assign py4 = LibBlockOutputSignalAddr(4, "", "", 0)
+  %assign py5 = LibBlockOutputSignalAddr(5, "", "", 0)
+  
+  %if IsModelReferenceSimTarget() || CodeFormat == "S-Function" || ::isRAccel
+    actuation_mat_Outputs_wrapper_accel(%<pu0>, %<py0>, %<py1>, %<py2>, %<py3>, %<py4>, %<py5>);
+  %else
+    actuation_mat_Outputs_wrapper(%<pu0>, %<py0>, %<py1>, %<py2>, %<py3>, %<py4>, %<py5>);
+  %endif
+
+  %%
+%endfunction
+
+
+%% [EOF] actuation_mat.tlc
+
diff --git a/controls/model/actuation_mat_wrapper.c b/controls/model/actuation_mat_wrapper.c
new file mode 100644
index 0000000000000000000000000000000000000000..4375a7acdc21288c76f16edf5466ae7176be0714
--- /dev/null
+++ b/controls/model/actuation_mat_wrapper.c
@@ -0,0 +1,60 @@
+
+/*
+ * Include Files
+ *
+ */
+#if defined(MATLAB_MEX_FILE)
+#include "tmwtypes.h"
+#include "simstruc_types.h"
+#else
+#define SIMPLIFIED_RTWTYPES_COMPATIBILITY
+#include "rtwtypes.h"
+#undef SIMPLIFIED_RTWTYPES_COMPATIBILITY
+#endif
+
+
+
+/* %%%-SFUNWIZ_wrapper_includes_Changes_BEGIN --- EDIT HERE TO _END */
+#include <math.h>
+/* %%%-SFUNWIZ_wrapper_includes_Changes_END --- EDIT HERE TO _BEGIN */
+#define u_width 1
+#define y_width 1
+#define y_1_width 1
+#define y_2_width 1
+#define y_3_width 1
+#define y_4_width 1
+#define y_5_width 1
+
+/*
+ * Create external references here.  
+ *
+ */
+/* %%%-SFUNWIZ_wrapper_externs_Changes_BEGIN --- EDIT HERE TO _END */
+/* extern double func(double a); */
+extern 
+/* %%%-SFUNWIZ_wrapper_externs_Changes_END --- EDIT HERE TO _BEGIN */
+
+/*
+ * Output function
+ *
+ */
+void actuation_mat_Outputs_wrapper(const real_T *P,
+			real_T *B_omega,
+			real_T *euler_angles,
+			real_T *B_vo,
+			real_T *E_ro,
+			real_T *B_vo_dot,
+			real_T *B_g)
+{
+/* %%%-SFUNWIZ_wrapper_Outputs_Changes_BEGIN --- EDIT HERE TO _END */
+/* This sample sets the output equal to the input
+      y0[0] = u0[0]; 
+ For complex signals use: y0[0].re = u0[0].re; 
+      y0[0].im = u0[0].im;
+      y1[0].re = u1[0].re;
+      y1[0].im = u1[0].im;
+ */
+/* %%%-SFUNWIZ_wrapper_Outputs_Changes_END --- EDIT HERE TO _BEGIN */
+}
+
+
diff --git a/controls/model/drone_gamepad_input.m b/controls/model/drone_gamepad_input.m
new file mode 100644
index 0000000000000000000000000000000000000000..9ab877fddbf5250bc16f87166ca585056fd001bc
--- /dev/null
+++ b/controls/model/drone_gamepad_input.m
@@ -0,0 +1,29 @@
+function setpoint = drone_gamepad_input(yaw_i, elevation_i, y_i, x_i, gamepad)
+
+input = read(gamepad);
+
+yaw_add = 0;
+elevation_add = 0;
+y_add = 0;
+x_add = 0;
+
+if abs(input(1)) > 0.1
+    yaw_add = input(1);
+end
+if abs(input(2)) > 0.1
+    elevation_add = input(2);
+end
+if abs(input(4)) > 0.1
+    y_add = input(4);
+end
+if abs(input(5)) > 0.1
+    x_add = input(5);
+end
+
+
+yaw = yaw_add + yaw_i;
+elevation = elevation_add + elevation_i;
+y = y_add + y_i;
+x = x_add + x_i;
+
+setpoint = [yaw, elevation, y, x];  
diff --git a/controls/model/modelParameters.m b/controls/model/modelParameters.m
index 30bda9a41410236868c9e04b964bc3b692c655b6..bcd3320d9ec1863691bbcd84fbd13c5d6aa9941a 100644
--- a/controls/model/modelParameters.m
+++ b/controls/model/modelParameters.m
@@ -14,7 +14,7 @@
 
 % Define Simulink Runtime (if logAnalysisToggle is selected, this will be
 % automatically set based on the log files time)
-     runtime = 40;
+     runtime = 1000;
     
 % Model Parameters
     m = 1.216;                          % Quadrotor + battery mass
diff --git a/controls/model/rtwmakecfg.m b/controls/model/rtwmakecfg.m
new file mode 100644
index 0000000000000000000000000000000000000000..a0e1421a09a3a38c1027e05603c69f34fb28d6dd
--- /dev/null
+++ b/controls/model/rtwmakecfg.m
@@ -0,0 +1,66 @@
+function makeInfo=rtwmakecfg()
+%RTWMAKECFG.m adds include and source directories to rtw make files.
+%  makeInfo=RTWMAKECFG returns a structured array containing
+%  following field:
+%     makeInfo.includePath - cell array containing additional include
+%                            directories. Those directories will be
+%                            expanded into include instructions of Simulink
+%                            Coder generated make files.
+%
+%     makeInfo.sourcePath  - cell array containing additional source
+%                            directories. Those directories will be
+%                            expanded into rules of Simulink Coder generated 
+%                            make files.
+makeInfo.includePath = {};
+makeInfo.sourcePath  = {};
+makeInfo.linkLibsObjs = {};
+
+%<Generated by S-Function Builder 3.0. DO NOT REMOVE>
+
+sfBuilderBlocksByMaskType = find_system(bdroot,'FollowLinks','on','LookUnderMasks','on','MaskType','S-Function Builder');
+sfBuilderBlocksByCallback = find_system(bdroot,'OpenFcn','sfunctionwizard(gcbh)');
+sfBuilderBlocksDeployed   = find_system(bdroot,'BlockType','S-Function','SFunctionDeploymentMode','on');
+sfBuilderBlocks = {sfBuilderBlocksByMaskType{:} sfBuilderBlocksByCallback{:} sfBuilderBlocksDeployed{:}};
+sfBuilderBlocks = unique(sfBuilderBlocks);
+if isempty(sfBuilderBlocks)
+   return;
+end
+sfBuilderBlockNameMATFile = cell(1, length(sfBuilderBlocks));
+for idx = 1:length(sfBuilderBlocks)
+   sfBuilderBlockNameMATFile{idx} = get_param(sfBuilderBlocks{idx},'FunctionName');
+   sfBuilderBlockNameMATFile{idx} = ['.' filesep 'SFB__' char(sfBuilderBlockNameMATFile{idx}) '__SFB.mat'];
+end
+sfBuilderBlockNameMATFile = unique(sfBuilderBlockNameMATFile);
+for idx = 1:length(sfBuilderBlockNameMATFile)
+   if exist(sfBuilderBlockNameMATFile{idx}, 'file')
+      loadedData = load(sfBuilderBlockNameMATFile{idx});
+      if isfield(loadedData,'SFBInfoStruct')
+         makeInfo = UpdateMakeInfo(makeInfo,loadedData.SFBInfoStruct);
+         clear loadedData;
+      end
+   end
+end
+
+function updatedMakeInfo = UpdateMakeInfo(makeInfo,SFBInfoStruct)
+updatedMakeInfo = {};
+if isfield(makeInfo,'includePath')
+   if isfield(SFBInfoStruct,'includePath')
+      updatedMakeInfo.includePath = {makeInfo.includePath{:} SFBInfoStruct.includePath{:}};
+   else
+      updatedMakeInfo.includePath = {makeInfo.includePath{:}};
+   end
+end
+if isfield(makeInfo,'sourcePath')
+   if isfield(SFBInfoStruct,'sourcePath')
+      updatedMakeInfo.sourcePath = {makeInfo.sourcePath{:} SFBInfoStruct.sourcePath{:}};
+   else
+      updatedMakeInfo.sourcePath = {makeInfo.sourcePath{:}};
+   end
+end
+if isfield(makeInfo,'linkLibsObjs')
+   if isfield(SFBInfoStruct,'additionalLibraries')
+      updatedMakeInfo.linkLibsObjs = {makeInfo.linkLibsObjs{:} SFBInfoStruct.additionalLibraries{:}};
+   else
+      updatedMakeInfo.linkLibsObjs = {makeInfo.linkLibsObjs{:}};
+   end
+end
diff --git a/crazyflie_demos/basic_hover_demo.py b/crazyflie_demos/basic_hover_demo.py
new file mode 100644
index 0000000000000000000000000000000000000000..96682a983355eb0944eb3bfbf983bec30150e881
--- /dev/null
+++ b/crazyflie_demos/basic_hover_demo.py
@@ -0,0 +1,158 @@
+#!/usr/bin/env python3
+# Demo that makes one Crazyflie take off 30cm above the first controller found
+# Using the controller trigger it is then possible to 'grab' the Crazyflie
+# and to make it move.
+import sys
+import time
+
+import cflib.crtp
+from cflib.crazyflie import Crazyflie
+from cflib.crazyflie.log import LogConfig
+from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
+from cflib.crazyflie.syncLogger import SyncLogger
+
+# URI to the Crazyflie to connect to
+uri = 'radio://0/90/2M'
+
+
+def wait_for_position_estimator(scf):
+    print('Waiting for estimator to find position...')
+
+    log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
+    log_config.add_variable('kalman.varPX', 'float')
+    log_config.add_variable('kalman.varPY', 'float')
+    log_config.add_variable('kalman.varPZ', 'float')
+
+    var_y_history = [1000] * 10
+    var_x_history = [1000] * 10
+    var_z_history = [1000] * 10
+
+    threshold = 0.001
+
+    with SyncLogger(scf, log_config) as logger:
+        for log_entry in logger:
+            data = log_entry[1]
+
+            var_x_history.append(data['kalman.varPX'])
+            var_x_history.pop(0)
+            var_y_history.append(data['kalman.varPY'])
+            var_y_history.pop(0)
+            var_z_history.append(data['kalman.varPZ'])
+            var_z_history.pop(0)
+
+            min_x = min(var_x_history)
+            max_x = max(var_x_history)
+            min_y = min(var_y_history)
+            max_y = max(var_y_history)
+            min_z = min(var_z_history)
+            max_z = max(var_z_history)
+
+            # print("{} {} {}".
+            #       format(max_x - min_x, max_y - min_y, max_z - min_z))
+
+            if (max_x - min_x) < threshold and (
+                    max_y - min_y) < threshold and (
+                    max_z - min_z) < threshold:
+                break
+
+
+def reset_estimator(scf):
+    cf = scf.cf
+    cf.param.set_value('kalman.resetEstimation', '1')
+    time.sleep(0.1)
+    cf.param.set_value('kalman.resetEstimation', '0')
+
+    wait_for_position_estimator(cf)
+
+
+def position_callback(timestamp, data, logconf):
+    x = data['kalman.stateX']
+    y = data['kalman.stateY']
+    z = data['kalman.stateZ']
+    print('pos: ({}, {}, {})'.format(x, y, z))
+
+
+def start_position_printing(scf):
+    log_conf = LogConfig(name='Position', period_in_ms=500)
+    log_conf.add_variable('kalman.stateX', 'float')
+    log_conf.add_variable('kalman.stateY', 'float')
+    log_conf.add_variable('kalman.stateZ', 'float')
+
+    scf.cf.log.add_config(log_conf)
+    log_conf.data_received_cb.add_callback(position_callback)
+    log_conf.start()
+
+
+def vector_substract(v0, v1):
+    return [v0[0] - v1[0], v0[1] - v1[1], v0[2] - v1[2]]
+
+
+def vector_add(v0, v1):
+    return [v0[0] + v1[0], v0[1] + v1[1], v0[2] + v1[2]]
+
+
+def fly_in_rectangle(cf, forward_dist, sideways_dist, move_time, wait_time):
+    # left
+    cf.high_level_commander.go_to(
+        0, sideways_dist, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+    # forward
+    cf.high_level_commander.go_to(
+        forward_dist, 0, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+    # right
+    cf.high_level_commander.go_to(
+        0, -sideways_dist, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+    # backwards
+    cf.high_level_commander.go_to(
+        -forward_dist, 0, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+
+def run_sequence(scf):
+    cf = scf.cf
+
+    setpoint = [0, 0, 2]
+
+    print("Initiating sequence")
+
+    setpoint = [0, 0, .5]
+
+    z_target = 0.66
+    move_dist = 0.2
+    move_vel = 0.2
+
+    cf.param.set_value('commander.enHighLevel', '1')
+    cf.high_level_commander.takeoff(z_target, 1)
+    time.sleep(3)
+
+    for i in range(0, 10):
+        fly_in_rectangle(cf, 1, 0.6, 2.5, 4)
+
+    time.sleep(3)
+    # land
+    cf.high_level_commander.land(0, z_target / move_vel)
+    time.sleep(10)
+    print("done")
+    cf.commander.send_setpoint(0, 0, 0, 0)
+    # Make sure that the last packet leaves before the link is closed
+    # since the message queue is not flushed before closing
+    time.sleep(0.1)
+
+
+if __name__ == '__main__':
+    cflib.crtp.init_drivers()
+
+    with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
+
+        reset_estimator(scf)
+        run_sequence(scf)
+
diff --git a/crazyflie_demos/basic_hover_demo_matlab.py b/crazyflie_demos/basic_hover_demo_matlab.py
new file mode 100644
index 0000000000000000000000000000000000000000..ba6678096d275026b8b045d62a7fae12dfc04781
--- /dev/null
+++ b/crazyflie_demos/basic_hover_demo_matlab.py
@@ -0,0 +1,371 @@
+#!/usr/bin/env python3
+# Demo that makes one Crazyflie take off 30cm above the first controller found
+# Using the controller trigger it is then possible to 'grab' the Crazyflie
+# and to make it move.
+import csv
+import sys
+import time
+
+import math
+import cflib.crtp
+from cflib.crazyflie import Crazyflie
+from cflib.crazyflie.log import LogConfig
+from cflib.crazyflie.syncCrazyflie import SyncCrazyflie
+from cflib.crazyflie.syncLogger import SyncLogger
+import matplotlib.pyplot as plt
+from pathlib import Path
+import numpy as np
+from scipy.io import savemat
+import matlab.engine
+
+# URI to the Crazyflie to connect to
+uri = 'radio://0/90/2M'
+
+pos_list = []
+rot_list = []
+
+start_time = time.time_ns()
+
+
+def wait_for_position_estimator(scf):
+    print('Waiting for estimator to find position...')
+
+    log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
+    log_config.add_variable('kalman.varPX', 'float')
+    log_config.add_variable('kalman.varPY', 'float')
+    log_config.add_variable('kalman.varPZ', 'float')
+
+    var_y_history = [1000] * 10
+    var_x_history = [1000] * 10
+    var_z_history = [1000] * 10
+
+    threshold = 0.001
+
+    with SyncLogger(scf, log_config) as logger:
+        for log_entry in logger:
+            data = log_entry[1]
+
+            var_x_history.append(data['kalman.varPX'])
+            var_x_history.pop(0)
+            var_y_history.append(data['kalman.varPY'])
+            var_y_history.pop(0)
+            var_z_history.append(data['kalman.varPZ'])
+            var_z_history.pop(0)
+
+            min_x = min(var_x_history)
+            max_x = max(var_x_history)
+            min_y = min(var_y_history)
+            max_y = max(var_y_history)
+            min_z = min(var_z_history)
+            max_z = max(var_z_history)
+
+            # print("{} {} {}".
+            #       format(max_x - min_x, max_y - min_y, max_z - min_z))
+
+            if (max_x - min_x) < threshold and (
+                    max_y - min_y) < threshold and (
+                    max_z - min_z) < threshold:
+                break
+
+
+
+def reset_estimator(scf):
+    cf = scf.cf
+    cf.param.set_value('kalman.resetEstimation', '1')
+    time.sleep(0.1)
+    cf.param.set_value('kalman.resetEstimation', '0')
+
+    wait_for_position_estimator(cf)
+
+
+def position_callback(timestamp, data, logconf):
+    x = data['kalman.stateX']
+    y = data['kalman.stateY']
+    z = data['kalman.stateZ']
+
+    time_since_start = (time.time_ns() - start_time) / (1000*1000*1000)
+    # print('{} pos: ({}, {}, {})'.format(time_since_start, x, y, z))
+
+    pos_list.append([time_since_start, x, y, z])
+
+
+def rotation_callback(timestamp, data, logconf):
+    q0 = data['kalman.q0']
+    q1 = data['kalman.q1']
+    q2 = data['kalman.q2']
+    q3 = data['kalman.q3']
+
+    time_since_start = (time.time_ns() - start_time) / (1000 * 1000 * 1000)
+
+    euler_angles = quaternion_to_euler(q0, q1, q2, q3)
+    yaw = euler_angles[0]
+    pitch = euler_angles[1]
+    roll = euler_angles[2]
+
+    print('{} rot: ({}, {}, {})'.format(time_since_start, yaw, pitch, roll))
+
+    rot_list.append([time_since_start, yaw, pitch, roll])
+
+
+def quaternion_to_euler(q0, q1, q2, q3):
+    """
+    Convert a quaternion to Euler angles (yaw, pitch, roll) in radians.
+
+    Args:
+        q0 (float): The scalar (real) part of the quaternion.
+        q1 (float): The x (imaginary) part of the quaternion.
+        q2 (float): The y (imaginary) part of the quaternion.
+        q3 (float): The z (imaginary) part of the quaternion.
+
+    Returns:
+        tuple: A tuple containing the yaw, pitch, and roll angles in radians.
+
+    Generated by ChatGPT :)
+    """
+    # roll (x-axis rotation)
+    sinr_cosp = 2 * (q0 * q1 + q2 * q3)
+    cosr_cosp = 1 - 2 * (q1**2 + q2**2)
+    roll = math.atan2(sinr_cosp, cosr_cosp)
+
+    # pitch (y-axis rotation)
+    sinp = 2 * (q0 * q2 - q3 * q1)
+    if abs(sinp) >= 1:
+        pitch = math.copysign(math.pi / 2, sinp)  # use 90 degrees if out of
+        # range
+    else:
+        pitch = math.asin(sinp)
+
+    # yaw (z-axis rotation)
+    siny_cosp = 2 * (q0 * q3 + q1 * q2)
+    cosy_cosp = 1 - 2 * (q2**2 + q3**2)
+    yaw = math.atan2(siny_cosp, cosy_cosp)
+
+    return (yaw, pitch, roll)
+
+
+def merge_time_series(rotations_list, positions_list):
+    """
+    Merge two asynchronous time series based on closest time values.
+
+    The function takes two lists of data, `rotations_list` and `positions_list`,
+    where each list contains a sequence of data points with the first element
+    representing a timestamp and the remaining elements representing data
+    values. The function merges the two lists based on the closest timestamp
+    values and returns a list of merged data points, with each point
+    represented as a list containing timestamp followed by positional and
+    rotational data.
+
+    Args:
+        rotations_list (list): A list of rotations data points, where each point
+            contains a timestamp and yaw, pitch, and roll values.
+        positions_list (list): A list of positions data points, where each point
+            contains a timestamp and x, y, and z values.
+
+    Returns:
+        merged_list (list): A list of merged data points, where each point
+            contains a timestamp and corresponding positional and rotational
+            data. If there are no overlapping timestamps between the two
+            input lists, the output list will be empty.
+
+    Generated by ChatGPT :)
+    """
+    # Initialize empty list to store merged data points
+    merged_list = []
+
+    # Loop through each position data point
+    for pos_point in positions_list:
+        # Get the timestamp for the current position data point
+        pos_time = pos_point[0]
+
+        # Initialize variable to store closest rotation data point
+        closest_rot_point = None
+        closest_rot_time_diff = float('inf')
+
+        # Loop through each rotation data point
+        for rot_point in rotations_list:
+            # Get the timestamp for the current rotation data point
+            rot_time = rot_point[0]
+
+            # Calculate the absolute difference between the position timestamp
+            # and the rotation timestamp
+            time_diff = abs(rot_time - pos_time)
+
+            # Check if the current rotation point is closer in time than the
+            # previously closest one
+            if time_diff < closest_rot_time_diff:
+                closest_rot_point = rot_point
+                closest_rot_time_diff = time_diff
+
+        # Check if a closest rotation point was found
+        if closest_rot_point is not None:
+            # Combine the position and rotation data points into a single
+            # merged point
+            merged_point = [pos_time] + pos_point[1:] + closest_rot_point[1:]
+
+            # Add the merged point to the list of merged data points
+            merged_list.append(merged_point)
+
+    # Return the list of merged data points
+    return merged_list
+
+
+def extract_along_dimension(list_in, dimension_index):
+    list_out = []
+
+    for i in range(0, len(list_in)):
+        list_out.append(list_in[i][dimension_index])
+
+    return list_out
+
+
+def start_position_printing(scf):
+    log_conf = LogConfig(name='Rotation', period_in_ms=10)
+    log_conf.add_variable('kalman.q0', 'float')
+    log_conf.add_variable('kalman.q1', 'float')
+    log_conf.add_variable('kalman.q2', 'float')
+    log_conf.add_variable('kalman.q3', 'float')
+
+    log_conf2 = LogConfig(name='Position', period_in_ms=10)
+    log_conf2.add_variable('kalman.stateX', 'float')
+    log_conf2.add_variable('kalman.stateY', 'float')
+    log_conf2.add_variable('kalman.stateZ', 'float')
+
+    scf.cf.log.add_config(log_conf)
+    scf.cf.log.add_config(log_conf2)
+
+    log_conf.data_received_cb.add_callback(rotation_callback)
+    log_conf.start()
+
+    log_conf2.data_received_cb.add_callback(position_callback)
+    log_conf2.start()
+
+
+def vector_substract(v0, v1):
+    return [v0[0] - v1[0], v0[1] - v1[1], v0[2] - v1[2]]
+
+
+def vector_add(v0, v1):
+    return [v0[0] + v1[0], v0[1] + v1[1], v0[2] + v1[2]]
+
+
+def fly_in_rectangle(cf, forward_dist, sideways_dist, move_time, wait_time):
+    # left
+    cf.high_level_commander.go_to(
+        0, sideways_dist, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+    # forward
+    cf.high_level_commander.go_to(
+        forward_dist, 0, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+    # right
+    cf.high_level_commander.go_to(
+        0, -sideways_dist, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+    # backwards
+    cf.high_level_commander.go_to(
+        -forward_dist, 0, 0, 0, move_time, relative=True
+    )
+    time.sleep(wait_time)
+
+
+def run_sequence(scf):
+    cf = scf.cf
+
+    setpoint = [0, 0, 2]
+
+    print("Initiating sequence")
+
+    setpoint = [0, 0, .5]
+
+    z_target = 0.66
+    move_dist = 0.2
+    move_vel = 0.2
+
+    cf.param.set_value('commander.enHighLevel', '1')
+    cf.high_level_commander.takeoff(z_target, 1)
+    time.sleep(3)
+
+    for i in range(0, 1):
+        fly_in_rectangle(cf, 0.5, 0.6, 2.5, 4)
+
+    time.sleep(3)
+    # land
+    cf.high_level_commander.land(0, z_target / move_vel)
+    time.sleep(3)
+    print("done")
+
+
+if __name__ == '__main__':
+    cflib.crtp.init_drivers()
+
+    with SyncCrazyflie(uri, cf=Crazyflie(rw_cache='./cache')) as scf:
+
+        # reset_estimator(scf) # if everything starts breaking, comment out
+        # this line and make sure the position looks good in cfclient. -Austin
+        start_position_printing(scf)
+        run_sequence(scf)
+
+        print(rot_list)
+        print(pos_list)
+
+        merged_list = merge_time_series(rot_list, pos_list)
+
+        print(merged_list)
+
+        times = extract_along_dimension(merged_list, 0)
+        xs = extract_along_dimension(merged_list, 1)
+        ys = extract_along_dimension(merged_list, 2)
+        zs = extract_along_dimension(merged_list, 3)
+        yaws = extract_along_dimension(merged_list, 4)
+        pitches = extract_along_dimension(merged_list, 5)
+        rolls = extract_along_dimension(merged_list, 6)
+
+        """
+        fig, axs = plt.subplots(1, 2)
+
+        axs[0].plot(times, xs, label='X')
+        axs[0].plot(times, ys, label='Y')
+        axs[0].plot(times, zs, label='Z')
+
+        # Add title and labels for the left subplot
+        axs[0].set_title('Left Subplot')
+        axs[0].set_xlabel('X-axis')
+        axs[0].set_ylabel('Y-axis')
+
+        # Add a legend to the left subplot
+        axs[0].legend()
+
+        axs[1].plot(times, yaws, label='Yaw')
+        axs[1].plot(times, pitches, label='Pitch')
+        axs[1].plot(times, rolls, label='Roll')
+
+        # Add title and labels for the right subplot
+        axs[1].set_title('Right Subplot')
+        axs[1].set_xlabel('X-axis')
+        axs[1].set_ylabel('Y-axis')
+
+        # Add a legend to the right subplot
+        axs[1].legend()
+
+        # Adjust the layout of the subplots
+        plt.tight_layout()
+
+        plt.show()
+        """
+
+        matlab_filepath = Path("./../controls/Sim-nonlinear-quad-example/"
+                               "Sim-nonlinear-quad-example")
+        csv_filename = "measured_flight_path.mat"
+
+        full_path = matlab_filepath.joinpath(csv_filename)
+
+        merged_list_np = np.array(merged_list).transpose()
+
+        mdic = {"measured_path": merged_list_np, "label": 'experiment'}
+        savemat(full_path, mdic)
diff --git a/crazyflie_demos/cache/06E08EEC.json b/crazyflie_demos/cache/06E08EEC.json
new file mode 100644
index 0000000000000000000000000000000000000000..7610b7afb3789182aa68ab7ddceb32d418cadfa1
--- /dev/null
+++ b/crazyflie_demos/cache/06E08EEC.json
@@ -0,0 +1,4526 @@
+{
+  "activeMarker": {
+    "btSns": {
+      "__class__": "LogTocElement",
+      "ident": 0,
+      "group": "activeMarker",
+      "name": "btSns",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "i2cOk": {
+      "__class__": "LogTocElement",
+      "ident": 1,
+      "group": "activeMarker",
+      "name": "i2cOk",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "motion": {
+    "motion": {
+      "__class__": "LogTocElement",
+      "ident": 2,
+      "group": "motion",
+      "name": "motion",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "deltaX": {
+      "__class__": "LogTocElement",
+      "ident": 3,
+      "group": "motion",
+      "name": "deltaX",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "deltaY": {
+      "__class__": "LogTocElement",
+      "ident": 4,
+      "group": "motion",
+      "name": "deltaY",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "shutter": {
+      "__class__": "LogTocElement",
+      "ident": 5,
+      "group": "motion",
+      "name": "shutter",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "maxRaw": {
+      "__class__": "LogTocElement",
+      "ident": 6,
+      "group": "motion",
+      "name": "maxRaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "minRaw": {
+      "__class__": "LogTocElement",
+      "ident": 7,
+      "group": "motion",
+      "name": "minRaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "Rawsum": {
+      "__class__": "LogTocElement",
+      "ident": 8,
+      "group": "motion",
+      "name": "Rawsum",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "outlierCount": {
+      "__class__": "LogTocElement",
+      "ident": 9,
+      "group": "motion",
+      "name": "outlierCount",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "squal": {
+      "__class__": "LogTocElement",
+      "ident": 10,
+      "group": "motion",
+      "name": "squal",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "std": {
+      "__class__": "LogTocElement",
+      "ident": 11,
+      "group": "motion",
+      "name": "std",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ring": {
+    "fadeTime": {
+      "__class__": "LogTocElement",
+      "ident": 12,
+      "group": "ring",
+      "name": "fadeTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "loco": {
+    "mode": {
+      "__class__": "LogTocElement",
+      "ident": 13,
+      "group": "loco",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "spiWr": {
+      "__class__": "LogTocElement",
+      "ident": 14,
+      "group": "loco",
+      "name": "spiWr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "spiRe": {
+      "__class__": "LogTocElement",
+      "ident": 15,
+      "group": "loco",
+      "name": "spiRe",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ranging": {
+    "state": {
+      "__class__": "LogTocElement",
+      "ident": 16,
+      "group": "ranging",
+      "name": "state",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "distance0": {
+      "__class__": "LogTocElement",
+      "ident": 17,
+      "group": "ranging",
+      "name": "distance0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance1": {
+      "__class__": "LogTocElement",
+      "ident": 18,
+      "group": "ranging",
+      "name": "distance1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance2": {
+      "__class__": "LogTocElement",
+      "ident": 19,
+      "group": "ranging",
+      "name": "distance2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance3": {
+      "__class__": "LogTocElement",
+      "ident": 20,
+      "group": "ranging",
+      "name": "distance3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance4": {
+      "__class__": "LogTocElement",
+      "ident": 21,
+      "group": "ranging",
+      "name": "distance4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance5": {
+      "__class__": "LogTocElement",
+      "ident": 22,
+      "group": "ranging",
+      "name": "distance5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance6": {
+      "__class__": "LogTocElement",
+      "ident": 23,
+      "group": "ranging",
+      "name": "distance6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance7": {
+      "__class__": "LogTocElement",
+      "ident": 24,
+      "group": "ranging",
+      "name": "distance7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure0": {
+      "__class__": "LogTocElement",
+      "ident": 25,
+      "group": "ranging",
+      "name": "pressure0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure1": {
+      "__class__": "LogTocElement",
+      "ident": 26,
+      "group": "ranging",
+      "name": "pressure1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure2": {
+      "__class__": "LogTocElement",
+      "ident": 27,
+      "group": "ranging",
+      "name": "pressure2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure3": {
+      "__class__": "LogTocElement",
+      "ident": 28,
+      "group": "ranging",
+      "name": "pressure3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure4": {
+      "__class__": "LogTocElement",
+      "ident": 29,
+      "group": "ranging",
+      "name": "pressure4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure5": {
+      "__class__": "LogTocElement",
+      "ident": 30,
+      "group": "ranging",
+      "name": "pressure5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure6": {
+      "__class__": "LogTocElement",
+      "ident": 31,
+      "group": "ranging",
+      "name": "pressure6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure7": {
+      "__class__": "LogTocElement",
+      "ident": 32,
+      "group": "ranging",
+      "name": "pressure7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "tdoa2": {
+    "d7-0": {
+      "__class__": "LogTocElement",
+      "ident": 33,
+      "group": "tdoa2",
+      "name": "d7-0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d0-1": {
+      "__class__": "LogTocElement",
+      "ident": 34,
+      "group": "tdoa2",
+      "name": "d0-1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d1-2": {
+      "__class__": "LogTocElement",
+      "ident": 35,
+      "group": "tdoa2",
+      "name": "d1-2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d2-3": {
+      "__class__": "LogTocElement",
+      "ident": 36,
+      "group": "tdoa2",
+      "name": "d2-3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d3-4": {
+      "__class__": "LogTocElement",
+      "ident": 37,
+      "group": "tdoa2",
+      "name": "d3-4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d4-5": {
+      "__class__": "LogTocElement",
+      "ident": 38,
+      "group": "tdoa2",
+      "name": "d4-5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d5-6": {
+      "__class__": "LogTocElement",
+      "ident": 39,
+      "group": "tdoa2",
+      "name": "d5-6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d6-7": {
+      "__class__": "LogTocElement",
+      "ident": 40,
+      "group": "tdoa2",
+      "name": "d6-7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc0": {
+      "__class__": "LogTocElement",
+      "ident": 41,
+      "group": "tdoa2",
+      "name": "cc0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc1": {
+      "__class__": "LogTocElement",
+      "ident": 42,
+      "group": "tdoa2",
+      "name": "cc1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc2": {
+      "__class__": "LogTocElement",
+      "ident": 43,
+      "group": "tdoa2",
+      "name": "cc2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc3": {
+      "__class__": "LogTocElement",
+      "ident": 44,
+      "group": "tdoa2",
+      "name": "cc3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc4": {
+      "__class__": "LogTocElement",
+      "ident": 45,
+      "group": "tdoa2",
+      "name": "cc4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc5": {
+      "__class__": "LogTocElement",
+      "ident": 46,
+      "group": "tdoa2",
+      "name": "cc5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc6": {
+      "__class__": "LogTocElement",
+      "ident": 47,
+      "group": "tdoa2",
+      "name": "cc6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc7": {
+      "__class__": "LogTocElement",
+      "ident": 48,
+      "group": "tdoa2",
+      "name": "cc7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "dist7-0": {
+      "__class__": "LogTocElement",
+      "ident": 49,
+      "group": "tdoa2",
+      "name": "dist7-0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist0-1": {
+      "__class__": "LogTocElement",
+      "ident": 50,
+      "group": "tdoa2",
+      "name": "dist0-1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist1-2": {
+      "__class__": "LogTocElement",
+      "ident": 51,
+      "group": "tdoa2",
+      "name": "dist1-2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist2-3": {
+      "__class__": "LogTocElement",
+      "ident": 52,
+      "group": "tdoa2",
+      "name": "dist2-3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist3-4": {
+      "__class__": "LogTocElement",
+      "ident": 53,
+      "group": "tdoa2",
+      "name": "dist3-4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist4-5": {
+      "__class__": "LogTocElement",
+      "ident": 54,
+      "group": "tdoa2",
+      "name": "dist4-5",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist5-6": {
+      "__class__": "LogTocElement",
+      "ident": 55,
+      "group": "tdoa2",
+      "name": "dist5-6",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist6-7": {
+      "__class__": "LogTocElement",
+      "ident": 56,
+      "group": "tdoa2",
+      "name": "dist6-7",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "twr": {
+    "rangingSuccessRate0": {
+      "__class__": "LogTocElement",
+      "ident": 57,
+      "group": "twr",
+      "name": "rangingSuccessRate0",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec0": {
+      "__class__": "LogTocElement",
+      "ident": 58,
+      "group": "twr",
+      "name": "rangingPerSec0",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate1": {
+      "__class__": "LogTocElement",
+      "ident": 59,
+      "group": "twr",
+      "name": "rangingSuccessRate1",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec1": {
+      "__class__": "LogTocElement",
+      "ident": 60,
+      "group": "twr",
+      "name": "rangingPerSec1",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate2": {
+      "__class__": "LogTocElement",
+      "ident": 61,
+      "group": "twr",
+      "name": "rangingSuccessRate2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec2": {
+      "__class__": "LogTocElement",
+      "ident": 62,
+      "group": "twr",
+      "name": "rangingPerSec2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate3": {
+      "__class__": "LogTocElement",
+      "ident": 63,
+      "group": "twr",
+      "name": "rangingSuccessRate3",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec3": {
+      "__class__": "LogTocElement",
+      "ident": 64,
+      "group": "twr",
+      "name": "rangingPerSec3",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate4": {
+      "__class__": "LogTocElement",
+      "ident": 65,
+      "group": "twr",
+      "name": "rangingSuccessRate4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec4": {
+      "__class__": "LogTocElement",
+      "ident": 66,
+      "group": "twr",
+      "name": "rangingPerSec4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate5": {
+      "__class__": "LogTocElement",
+      "ident": 67,
+      "group": "twr",
+      "name": "rangingSuccessRate5",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec5": {
+      "__class__": "LogTocElement",
+      "ident": 68,
+      "group": "twr",
+      "name": "rangingPerSec5",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "oa": {
+    "front": {
+      "__class__": "LogTocElement",
+      "ident": 69,
+      "group": "oa",
+      "name": "front",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "back": {
+      "__class__": "LogTocElement",
+      "ident": 70,
+      "group": "oa",
+      "name": "back",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "up": {
+      "__class__": "LogTocElement",
+      "ident": 71,
+      "group": "oa",
+      "name": "up",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "left": {
+      "__class__": "LogTocElement",
+      "ident": 72,
+      "group": "oa",
+      "name": "left",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "right": {
+      "__class__": "LogTocElement",
+      "ident": 73,
+      "group": "oa",
+      "name": "right",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "usd": {
+    "spiWrBps": {
+      "__class__": "LogTocElement",
+      "ident": 74,
+      "group": "usd",
+      "name": "spiWrBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "spiReBps": {
+      "__class__": "LogTocElement",
+      "ident": 75,
+      "group": "usd",
+      "name": "spiReBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "fatWrBps": {
+      "__class__": "LogTocElement",
+      "ident": 76,
+      "group": "usd",
+      "name": "fatWrBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "motor": {
+    "m1": {
+      "__class__": "LogTocElement",
+      "ident": 77,
+      "group": "motor",
+      "name": "m1",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m2": {
+      "__class__": "LogTocElement",
+      "ident": 78,
+      "group": "motor",
+      "name": "m2",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m3": {
+      "__class__": "LogTocElement",
+      "ident": 79,
+      "group": "motor",
+      "name": "m3",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m4": {
+      "__class__": "LogTocElement",
+      "ident": 80,
+      "group": "motor",
+      "name": "m4",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m1req": {
+      "__class__": "LogTocElement",
+      "ident": 81,
+      "group": "motor",
+      "name": "m1req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "m2req": {
+      "__class__": "LogTocElement",
+      "ident": 82,
+      "group": "motor",
+      "name": "m2req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "m3req": {
+      "__class__": "LogTocElement",
+      "ident": 83,
+      "group": "motor",
+      "name": "m3req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "m4req": {
+      "__class__": "LogTocElement",
+      "ident": 84,
+      "group": "motor",
+      "name": "m4req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    }
+  },
+  "pm": {
+    "vbat": {
+      "__class__": "LogTocElement",
+      "ident": 85,
+      "group": "pm",
+      "name": "vbat",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vbatMV": {
+      "__class__": "LogTocElement",
+      "ident": 86,
+      "group": "pm",
+      "name": "vbatMV",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "extVbat": {
+      "__class__": "LogTocElement",
+      "ident": 87,
+      "group": "pm",
+      "name": "extVbat",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "extVbatMV": {
+      "__class__": "LogTocElement",
+      "ident": 88,
+      "group": "pm",
+      "name": "extVbatMV",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "extCurr": {
+      "__class__": "LogTocElement",
+      "ident": 89,
+      "group": "pm",
+      "name": "extCurr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "chargeCurrent": {
+      "__class__": "LogTocElement",
+      "ident": 90,
+      "group": "pm",
+      "name": "chargeCurrent",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "state": {
+      "__class__": "LogTocElement",
+      "ident": 91,
+      "group": "pm",
+      "name": "state",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0
+    },
+    "batteryLevel": {
+      "__class__": "LogTocElement",
+      "ident": 92,
+      "group": "pm",
+      "name": "batteryLevel",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "radio": {
+    "rssi": {
+      "__class__": "LogTocElement",
+      "ident": 93,
+      "group": "radio",
+      "name": "rssi",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isConnected": {
+      "__class__": "LogTocElement",
+      "ident": 94,
+      "group": "radio",
+      "name": "isConnected",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "gyro": {
+    "xRaw": {
+      "__class__": "LogTocElement",
+      "ident": 95,
+      "group": "gyro",
+      "name": "xRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "yRaw": {
+      "__class__": "LogTocElement",
+      "ident": 96,
+      "group": "gyro",
+      "name": "yRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "zRaw": {
+      "__class__": "LogTocElement",
+      "ident": 97,
+      "group": "gyro",
+      "name": "zRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "xVariance": {
+      "__class__": "LogTocElement",
+      "ident": 98,
+      "group": "gyro",
+      "name": "xVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yVariance": {
+      "__class__": "LogTocElement",
+      "ident": 99,
+      "group": "gyro",
+      "name": "yVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zVariance": {
+      "__class__": "LogTocElement",
+      "ident": 100,
+      "group": "gyro",
+      "name": "zVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 101,
+      "group": "gyro",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 102,
+      "group": "gyro",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 103,
+      "group": "gyro",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "pid_attitude": {
+    "roll_outP": {
+      "__class__": "LogTocElement",
+      "ident": 104,
+      "group": "pid_attitude",
+      "name": "roll_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outI": {
+      "__class__": "LogTocElement",
+      "ident": 105,
+      "group": "pid_attitude",
+      "name": "roll_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outD": {
+      "__class__": "LogTocElement",
+      "ident": 106,
+      "group": "pid_attitude",
+      "name": "roll_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 107,
+      "group": "pid_attitude",
+      "name": "roll_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outP": {
+      "__class__": "LogTocElement",
+      "ident": 108,
+      "group": "pid_attitude",
+      "name": "pitch_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outI": {
+      "__class__": "LogTocElement",
+      "ident": 109,
+      "group": "pid_attitude",
+      "name": "pitch_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outD": {
+      "__class__": "LogTocElement",
+      "ident": 110,
+      "group": "pid_attitude",
+      "name": "pitch_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 111,
+      "group": "pid_attitude",
+      "name": "pitch_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outP": {
+      "__class__": "LogTocElement",
+      "ident": 112,
+      "group": "pid_attitude",
+      "name": "yaw_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outI": {
+      "__class__": "LogTocElement",
+      "ident": 113,
+      "group": "pid_attitude",
+      "name": "yaw_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outD": {
+      "__class__": "LogTocElement",
+      "ident": 114,
+      "group": "pid_attitude",
+      "name": "yaw_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 115,
+      "group": "pid_attitude",
+      "name": "yaw_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "pid_rate": {
+    "roll_outP": {
+      "__class__": "LogTocElement",
+      "ident": 116,
+      "group": "pid_rate",
+      "name": "roll_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outI": {
+      "__class__": "LogTocElement",
+      "ident": 117,
+      "group": "pid_rate",
+      "name": "roll_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outD": {
+      "__class__": "LogTocElement",
+      "ident": 118,
+      "group": "pid_rate",
+      "name": "roll_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 119,
+      "group": "pid_rate",
+      "name": "roll_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outP": {
+      "__class__": "LogTocElement",
+      "ident": 120,
+      "group": "pid_rate",
+      "name": "pitch_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outI": {
+      "__class__": "LogTocElement",
+      "ident": 121,
+      "group": "pid_rate",
+      "name": "pitch_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outD": {
+      "__class__": "LogTocElement",
+      "ident": 122,
+      "group": "pid_rate",
+      "name": "pitch_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 123,
+      "group": "pid_rate",
+      "name": "pitch_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outP": {
+      "__class__": "LogTocElement",
+      "ident": 124,
+      "group": "pid_rate",
+      "name": "yaw_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outI": {
+      "__class__": "LogTocElement",
+      "ident": 125,
+      "group": "pid_rate",
+      "name": "yaw_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outD": {
+      "__class__": "LogTocElement",
+      "ident": 126,
+      "group": "pid_rate",
+      "name": "yaw_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 127,
+      "group": "pid_rate",
+      "name": "yaw_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "colAv": {
+    "latency": {
+      "__class__": "LogTocElement",
+      "ident": 128,
+      "group": "colAv",
+      "name": "latency",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "ctrlINDI": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 129,
+      "group": "ctrlINDI",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 130,
+      "group": "ctrlINDI",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 131,
+      "group": "ctrlINDI",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 132,
+      "group": "ctrlINDI",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 133,
+      "group": "ctrlINDI",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 134,
+      "group": "ctrlINDI",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 135,
+      "group": "ctrlINDI",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_p": {
+      "__class__": "LogTocElement",
+      "ident": 136,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_q": {
+      "__class__": "LogTocElement",
+      "ident": 137,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_r": {
+      "__class__": "LogTocElement",
+      "ident": 138,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_p": {
+      "__class__": "LogTocElement",
+      "ident": 139,
+      "group": "ctrlINDI",
+      "name": "du_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_q": {
+      "__class__": "LogTocElement",
+      "ident": 140,
+      "group": "ctrlINDI",
+      "name": "du_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_r": {
+      "__class__": "LogTocElement",
+      "ident": 141,
+      "group": "ctrlINDI",
+      "name": "du_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_p": {
+      "__class__": "LogTocElement",
+      "ident": 142,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_q": {
+      "__class__": "LogTocElement",
+      "ident": 143,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_r": {
+      "__class__": "LogTocElement",
+      "ident": 144,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[0]": {
+      "__class__": "LogTocElement",
+      "ident": 145,
+      "group": "ctrlINDI",
+      "name": "rate_d[0]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[1]": {
+      "__class__": "LogTocElement",
+      "ident": 146,
+      "group": "ctrlINDI",
+      "name": "rate_d[1]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[2]": {
+      "__class__": "LogTocElement",
+      "ident": 147,
+      "group": "ctrlINDI",
+      "name": "rate_d[2]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_p": {
+      "__class__": "LogTocElement",
+      "ident": 148,
+      "group": "ctrlINDI",
+      "name": "uf_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_q": {
+      "__class__": "LogTocElement",
+      "ident": 149,
+      "group": "ctrlINDI",
+      "name": "uf_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_r": {
+      "__class__": "LogTocElement",
+      "ident": 150,
+      "group": "ctrlINDI",
+      "name": "uf_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_p": {
+      "__class__": "LogTocElement",
+      "ident": 151,
+      "group": "ctrlINDI",
+      "name": "Omega_f_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_q": {
+      "__class__": "LogTocElement",
+      "ident": 152,
+      "group": "ctrlINDI",
+      "name": "Omega_f_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_r": {
+      "__class__": "LogTocElement",
+      "ident": 153,
+      "group": "ctrlINDI",
+      "name": "Omega_f_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_p": {
+      "__class__": "LogTocElement",
+      "ident": 154,
+      "group": "ctrlINDI",
+      "name": "n_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_q": {
+      "__class__": "LogTocElement",
+      "ident": 155,
+      "group": "ctrlINDI",
+      "name": "n_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_r": {
+      "__class__": "LogTocElement",
+      "ident": 156,
+      "group": "ctrlINDI",
+      "name": "n_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrlMel": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 157,
+      "group": "ctrlMel",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 158,
+      "group": "ctrlMel",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 159,
+      "group": "ctrlMel",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 160,
+      "group": "ctrlMel",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 161,
+      "group": "ctrlMel",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 162,
+      "group": "ctrlMel",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 163,
+      "group": "ctrlMel",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accelz": {
+      "__class__": "LogTocElement",
+      "ident": 164,
+      "group": "ctrlMel",
+      "name": "accelz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdx": {
+      "__class__": "LogTocElement",
+      "ident": 165,
+      "group": "ctrlMel",
+      "name": "zdx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdy": {
+      "__class__": "LogTocElement",
+      "ident": 166,
+      "group": "ctrlMel",
+      "name": "zdy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdz": {
+      "__class__": "LogTocElement",
+      "ident": 167,
+      "group": "ctrlMel",
+      "name": "zdz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_x": {
+      "__class__": "LogTocElement",
+      "ident": 168,
+      "group": "ctrlMel",
+      "name": "i_err_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_y": {
+      "__class__": "LogTocElement",
+      "ident": 169,
+      "group": "ctrlMel",
+      "name": "i_err_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_z": {
+      "__class__": "LogTocElement",
+      "ident": 170,
+      "group": "ctrlMel",
+      "name": "i_err_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "controller": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 171,
+      "group": "controller",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 172,
+      "group": "controller",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 173,
+      "group": "controller",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 174,
+      "group": "controller",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 175,
+      "group": "controller",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 176,
+      "group": "controller",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 177,
+      "group": "controller",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accelz": {
+      "__class__": "LogTocElement",
+      "ident": 178,
+      "group": "controller",
+      "name": "accelz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "actuatorThrust": {
+      "__class__": "LogTocElement",
+      "ident": 179,
+      "group": "controller",
+      "name": "actuatorThrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 180,
+      "group": "controller",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 181,
+      "group": "controller",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 182,
+      "group": "controller",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rollRate": {
+      "__class__": "LogTocElement",
+      "ident": 183,
+      "group": "controller",
+      "name": "rollRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitchRate": {
+      "__class__": "LogTocElement",
+      "ident": 184,
+      "group": "controller",
+      "name": "pitchRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yawRate": {
+      "__class__": "LogTocElement",
+      "ident": 185,
+      "group": "controller",
+      "name": "yawRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ctr_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 186,
+      "group": "controller",
+      "name": "ctr_yaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "ext_pos": {
+    "X": {
+      "__class__": "LogTocElement",
+      "ident": 187,
+      "group": "ext_pos",
+      "name": "X",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Y": {
+      "__class__": "LogTocElement",
+      "ident": 188,
+      "group": "ext_pos",
+      "name": "Y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Z": {
+      "__class__": "LogTocElement",
+      "ident": 189,
+      "group": "ext_pos",
+      "name": "Z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "locSrv": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 190,
+      "group": "locSrv",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 191,
+      "group": "locSrv",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 192,
+      "group": "locSrv",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 193,
+      "group": "locSrv",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 194,
+      "group": "locSrv",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 195,
+      "group": "locSrv",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 196,
+      "group": "locSrv",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "locSrvZ": {
+    "tick": {
+      "__class__": "LogTocElement",
+      "ident": 197,
+      "group": "locSrvZ",
+      "name": "tick",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "crtp": {
+    "rxRate": {
+      "__class__": "LogTocElement",
+      "ident": 198,
+      "group": "crtp",
+      "name": "rxRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "txRate": {
+      "__class__": "LogTocElement",
+      "ident": 199,
+      "group": "crtp",
+      "name": "txRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "kalman": {
+    "inFlight": {
+      "__class__": "LogTocElement",
+      "ident": 200,
+      "group": "kalman",
+      "name": "inFlight",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "stateX": {
+      "__class__": "LogTocElement",
+      "ident": 201,
+      "group": "kalman",
+      "name": "stateX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateY": {
+      "__class__": "LogTocElement",
+      "ident": 202,
+      "group": "kalman",
+      "name": "stateY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateZ": {
+      "__class__": "LogTocElement",
+      "ident": 203,
+      "group": "kalman",
+      "name": "stateZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePX": {
+      "__class__": "LogTocElement",
+      "ident": 204,
+      "group": "kalman",
+      "name": "statePX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePY": {
+      "__class__": "LogTocElement",
+      "ident": 205,
+      "group": "kalman",
+      "name": "statePY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePZ": {
+      "__class__": "LogTocElement",
+      "ident": 206,
+      "group": "kalman",
+      "name": "statePZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD0": {
+      "__class__": "LogTocElement",
+      "ident": 207,
+      "group": "kalman",
+      "name": "stateD0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD1": {
+      "__class__": "LogTocElement",
+      "ident": 208,
+      "group": "kalman",
+      "name": "stateD1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD2": {
+      "__class__": "LogTocElement",
+      "ident": 209,
+      "group": "kalman",
+      "name": "stateD2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varX": {
+      "__class__": "LogTocElement",
+      "ident": 210,
+      "group": "kalman",
+      "name": "varX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varY": {
+      "__class__": "LogTocElement",
+      "ident": 211,
+      "group": "kalman",
+      "name": "varY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varZ": {
+      "__class__": "LogTocElement",
+      "ident": 212,
+      "group": "kalman",
+      "name": "varZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPX": {
+      "__class__": "LogTocElement",
+      "ident": 213,
+      "group": "kalman",
+      "name": "varPX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPY": {
+      "__class__": "LogTocElement",
+      "ident": 214,
+      "group": "kalman",
+      "name": "varPY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPZ": {
+      "__class__": "LogTocElement",
+      "ident": 215,
+      "group": "kalman",
+      "name": "varPZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD0": {
+      "__class__": "LogTocElement",
+      "ident": 216,
+      "group": "kalman",
+      "name": "varD0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD1": {
+      "__class__": "LogTocElement",
+      "ident": 217,
+      "group": "kalman",
+      "name": "varD1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD2": {
+      "__class__": "LogTocElement",
+      "ident": 218,
+      "group": "kalman",
+      "name": "varD2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q0": {
+      "__class__": "LogTocElement",
+      "ident": 219,
+      "group": "kalman",
+      "name": "q0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q1": {
+      "__class__": "LogTocElement",
+      "ident": 220,
+      "group": "kalman",
+      "name": "q1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q2": {
+      "__class__": "LogTocElement",
+      "ident": 221,
+      "group": "kalman",
+      "name": "q2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q3": {
+      "__class__": "LogTocElement",
+      "ident": 222,
+      "group": "kalman",
+      "name": "q3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtUpdate": {
+      "__class__": "LogTocElement",
+      "ident": 223,
+      "group": "kalman",
+      "name": "rtUpdate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtPred": {
+      "__class__": "LogTocElement",
+      "ident": 224,
+      "group": "kalman",
+      "name": "rtPred",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtFinal": {
+      "__class__": "LogTocElement",
+      "ident": 225,
+      "group": "kalman",
+      "name": "rtFinal",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "outlierf": {
+    "lhWin": {
+      "__class__": "LogTocElement",
+      "ident": 226,
+      "group": "outlierf",
+      "name": "lhWin",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket0": {
+      "__class__": "LogTocElement",
+      "ident": 227,
+      "group": "outlierf",
+      "name": "bucket0",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket1": {
+      "__class__": "LogTocElement",
+      "ident": 228,
+      "group": "outlierf",
+      "name": "bucket1",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket2": {
+      "__class__": "LogTocElement",
+      "ident": 229,
+      "group": "outlierf",
+      "name": "bucket2",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket3": {
+      "__class__": "LogTocElement",
+      "ident": 230,
+      "group": "outlierf",
+      "name": "bucket3",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket4": {
+      "__class__": "LogTocElement",
+      "ident": 231,
+      "group": "outlierf",
+      "name": "bucket4",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "accLev": {
+      "__class__": "LogTocElement",
+      "ident": 232,
+      "group": "outlierf",
+      "name": "accLev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "errD": {
+      "__class__": "LogTocElement",
+      "ident": 233,
+      "group": "outlierf",
+      "name": "errD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "estimator": {
+    "rtApnd": {
+      "__class__": "LogTocElement",
+      "ident": 234,
+      "group": "estimator",
+      "name": "rtApnd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtRej": {
+      "__class__": "LogTocElement",
+      "ident": 235,
+      "group": "estimator",
+      "name": "rtRej",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "extrx": {
+    "thrust": {
+      "__class__": "LogTocElement",
+      "ident": 236,
+      "group": "extrx",
+      "name": "thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 237,
+      "group": "extrx",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 238,
+      "group": "extrx",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rollRate": {
+      "__class__": "LogTocElement",
+      "ident": 239,
+      "group": "extrx",
+      "name": "rollRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitchRate": {
+      "__class__": "LogTocElement",
+      "ident": 240,
+      "group": "extrx",
+      "name": "pitchRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yawRate": {
+      "__class__": "LogTocElement",
+      "ident": 241,
+      "group": "extrx",
+      "name": "yawRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zVel": {
+      "__class__": "LogTocElement",
+      "ident": 242,
+      "group": "extrx",
+      "name": "zVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "AltHold": {
+      "__class__": "LogTocElement",
+      "ident": 243,
+      "group": "extrx",
+      "name": "AltHold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "Arm": {
+      "__class__": "LogTocElement",
+      "ident": 244,
+      "group": "extrx",
+      "name": "Arm",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "extrx_raw": {
+    "ch0": {
+      "__class__": "LogTocElement",
+      "ident": 245,
+      "group": "extrx_raw",
+      "name": "ch0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch1": {
+      "__class__": "LogTocElement",
+      "ident": 246,
+      "group": "extrx_raw",
+      "name": "ch1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch2": {
+      "__class__": "LogTocElement",
+      "ident": 247,
+      "group": "extrx_raw",
+      "name": "ch2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch3": {
+      "__class__": "LogTocElement",
+      "ident": 248,
+      "group": "extrx_raw",
+      "name": "ch3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch4": {
+      "__class__": "LogTocElement",
+      "ident": 249,
+      "group": "extrx_raw",
+      "name": "ch4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch5": {
+      "__class__": "LogTocElement",
+      "ident": 250,
+      "group": "extrx_raw",
+      "name": "ch5",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch6": {
+      "__class__": "LogTocElement",
+      "ident": 251,
+      "group": "extrx_raw",
+      "name": "ch6",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch7": {
+      "__class__": "LogTocElement",
+      "ident": 252,
+      "group": "extrx_raw",
+      "name": "ch7",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "health": {
+    "motorVarXM1": {
+      "__class__": "LogTocElement",
+      "ident": 253,
+      "group": "health",
+      "name": "motorVarXM1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM1": {
+      "__class__": "LogTocElement",
+      "ident": 254,
+      "group": "health",
+      "name": "motorVarYM1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM2": {
+      "__class__": "LogTocElement",
+      "ident": 255,
+      "group": "health",
+      "name": "motorVarXM2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM2": {
+      "__class__": "LogTocElement",
+      "ident": 256,
+      "group": "health",
+      "name": "motorVarYM2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM3": {
+      "__class__": "LogTocElement",
+      "ident": 257,
+      "group": "health",
+      "name": "motorVarXM3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM3": {
+      "__class__": "LogTocElement",
+      "ident": 258,
+      "group": "health",
+      "name": "motorVarYM3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM4": {
+      "__class__": "LogTocElement",
+      "ident": 259,
+      "group": "health",
+      "name": "motorVarXM4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM4": {
+      "__class__": "LogTocElement",
+      "ident": 260,
+      "group": "health",
+      "name": "motorVarYM4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorPass": {
+      "__class__": "LogTocElement",
+      "ident": 261,
+      "group": "health",
+      "name": "motorPass",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "batterySag": {
+      "__class__": "LogTocElement",
+      "ident": 262,
+      "group": "health",
+      "name": "batterySag",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "batteryPass": {
+      "__class__": "LogTocElement",
+      "ident": 263,
+      "group": "health",
+      "name": "batteryPass",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "motorTestCount": {
+      "__class__": "LogTocElement",
+      "ident": 264,
+      "group": "health",
+      "name": "motorTestCount",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "memTst": {
+    "errCntW": {
+      "__class__": "LogTocElement",
+      "ident": 265,
+      "group": "memTst",
+      "name": "errCntW",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "posCtrlIndi": {
+    "posRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 266,
+      "group": "posCtrlIndi",
+      "name": "posRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "posRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 267,
+      "group": "posCtrlIndi",
+      "name": "posRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "posRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 268,
+      "group": "posCtrlIndi",
+      "name": "posRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_x": {
+      "__class__": "LogTocElement",
+      "ident": 269,
+      "group": "posCtrlIndi",
+      "name": "velS_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_y": {
+      "__class__": "LogTocElement",
+      "ident": 270,
+      "group": "posCtrlIndi",
+      "name": "velS_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_z": {
+      "__class__": "LogTocElement",
+      "ident": 271,
+      "group": "posCtrlIndi",
+      "name": "velS_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 272,
+      "group": "posCtrlIndi",
+      "name": "velRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 273,
+      "group": "posCtrlIndi",
+      "name": "velRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 274,
+      "group": "posCtrlIndi",
+      "name": "velRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_roll": {
+      "__class__": "LogTocElement",
+      "ident": 275,
+      "group": "posCtrlIndi",
+      "name": "angS_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 276,
+      "group": "posCtrlIndi",
+      "name": "angS_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 277,
+      "group": "posCtrlIndi",
+      "name": "angS_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_roll": {
+      "__class__": "LogTocElement",
+      "ident": 278,
+      "group": "posCtrlIndi",
+      "name": "angF_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 279,
+      "group": "posCtrlIndi",
+      "name": "angF_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 280,
+      "group": "posCtrlIndi",
+      "name": "angF_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 281,
+      "group": "posCtrlIndi",
+      "name": "accRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 282,
+      "group": "posCtrlIndi",
+      "name": "accRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 283,
+      "group": "posCtrlIndi",
+      "name": "accRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_x": {
+      "__class__": "LogTocElement",
+      "ident": 284,
+      "group": "posCtrlIndi",
+      "name": "accS_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_y": {
+      "__class__": "LogTocElement",
+      "ident": 285,
+      "group": "posCtrlIndi",
+      "name": "accS_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_z": {
+      "__class__": "LogTocElement",
+      "ident": 286,
+      "group": "posCtrlIndi",
+      "name": "accS_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_x": {
+      "__class__": "LogTocElement",
+      "ident": 287,
+      "group": "posCtrlIndi",
+      "name": "accF_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_y": {
+      "__class__": "LogTocElement",
+      "ident": 288,
+      "group": "posCtrlIndi",
+      "name": "accF_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_z": {
+      "__class__": "LogTocElement",
+      "ident": 289,
+      "group": "posCtrlIndi",
+      "name": "accF_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_x": {
+      "__class__": "LogTocElement",
+      "ident": 290,
+      "group": "posCtrlIndi",
+      "name": "accFT_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_y": {
+      "__class__": "LogTocElement",
+      "ident": 291,
+      "group": "posCtrlIndi",
+      "name": "accFT_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_z": {
+      "__class__": "LogTocElement",
+      "ident": 292,
+      "group": "posCtrlIndi",
+      "name": "accFT_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_x": {
+      "__class__": "LogTocElement",
+      "ident": 293,
+      "group": "posCtrlIndi",
+      "name": "accErr_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_y": {
+      "__class__": "LogTocElement",
+      "ident": 294,
+      "group": "posCtrlIndi",
+      "name": "accErr_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_z": {
+      "__class__": "LogTocElement",
+      "ident": 295,
+      "group": "posCtrlIndi",
+      "name": "accErr_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "phi_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 296,
+      "group": "posCtrlIndi",
+      "name": "phi_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "theta_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 297,
+      "group": "posCtrlIndi",
+      "name": "theta_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 298,
+      "group": "posCtrlIndi",
+      "name": "T_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_inner": {
+      "__class__": "LogTocElement",
+      "ident": 299,
+      "group": "posCtrlIndi",
+      "name": "T_inner",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_inner_f": {
+      "__class__": "LogTocElement",
+      "ident": 300,
+      "group": "posCtrlIndi",
+      "name": "T_inner_f",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_incremented": {
+      "__class__": "LogTocElement",
+      "ident": 301,
+      "group": "posCtrlIndi",
+      "name": "T_incremented",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_phi": {
+      "__class__": "LogTocElement",
+      "ident": 302,
+      "group": "posCtrlIndi",
+      "name": "cmd_phi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_theta": {
+      "__class__": "LogTocElement",
+      "ident": 303,
+      "group": "posCtrlIndi",
+      "name": "cmd_theta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "posCtl": {
+    "targetVX": {
+      "__class__": "LogTocElement",
+      "ident": 304,
+      "group": "posCtl",
+      "name": "targetVX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetVY": {
+      "__class__": "LogTocElement",
+      "ident": 305,
+      "group": "posCtl",
+      "name": "targetVY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetVZ": {
+      "__class__": "LogTocElement",
+      "ident": 306,
+      "group": "posCtl",
+      "name": "targetVZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetX": {
+      "__class__": "LogTocElement",
+      "ident": 307,
+      "group": "posCtl",
+      "name": "targetX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetY": {
+      "__class__": "LogTocElement",
+      "ident": 308,
+      "group": "posCtl",
+      "name": "targetY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetZ": {
+      "__class__": "LogTocElement",
+      "ident": 309,
+      "group": "posCtl",
+      "name": "targetZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyVX": {
+      "__class__": "LogTocElement",
+      "ident": 310,
+      "group": "posCtl",
+      "name": "bodyVX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyVY": {
+      "__class__": "LogTocElement",
+      "ident": 311,
+      "group": "posCtl",
+      "name": "bodyVY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyX": {
+      "__class__": "LogTocElement",
+      "ident": 312,
+      "group": "posCtl",
+      "name": "bodyX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyY": {
+      "__class__": "LogTocElement",
+      "ident": 313,
+      "group": "posCtl",
+      "name": "bodyY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xp": {
+      "__class__": "LogTocElement",
+      "ident": 314,
+      "group": "posCtl",
+      "name": "Xp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xi": {
+      "__class__": "LogTocElement",
+      "ident": 315,
+      "group": "posCtl",
+      "name": "Xi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xd": {
+      "__class__": "LogTocElement",
+      "ident": 316,
+      "group": "posCtl",
+      "name": "Xd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xff": {
+      "__class__": "LogTocElement",
+      "ident": 317,
+      "group": "posCtl",
+      "name": "Xff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yp": {
+      "__class__": "LogTocElement",
+      "ident": 318,
+      "group": "posCtl",
+      "name": "Yp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yi": {
+      "__class__": "LogTocElement",
+      "ident": 319,
+      "group": "posCtl",
+      "name": "Yi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yd": {
+      "__class__": "LogTocElement",
+      "ident": 320,
+      "group": "posCtl",
+      "name": "Yd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yff": {
+      "__class__": "LogTocElement",
+      "ident": 321,
+      "group": "posCtl",
+      "name": "Yff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zp": {
+      "__class__": "LogTocElement",
+      "ident": 322,
+      "group": "posCtl",
+      "name": "Zp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zi": {
+      "__class__": "LogTocElement",
+      "ident": 323,
+      "group": "posCtl",
+      "name": "Zi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zd": {
+      "__class__": "LogTocElement",
+      "ident": 324,
+      "group": "posCtl",
+      "name": "Zd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zff": {
+      "__class__": "LogTocElement",
+      "ident": 325,
+      "group": "posCtl",
+      "name": "Zff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXp": {
+      "__class__": "LogTocElement",
+      "ident": 326,
+      "group": "posCtl",
+      "name": "VXp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXi": {
+      "__class__": "LogTocElement",
+      "ident": 327,
+      "group": "posCtl",
+      "name": "VXi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXd": {
+      "__class__": "LogTocElement",
+      "ident": 328,
+      "group": "posCtl",
+      "name": "VXd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXff": {
+      "__class__": "LogTocElement",
+      "ident": 329,
+      "group": "posCtl",
+      "name": "VXff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYp": {
+      "__class__": "LogTocElement",
+      "ident": 330,
+      "group": "posCtl",
+      "name": "VYp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYi": {
+      "__class__": "LogTocElement",
+      "ident": 331,
+      "group": "posCtl",
+      "name": "VYi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYd": {
+      "__class__": "LogTocElement",
+      "ident": 332,
+      "group": "posCtl",
+      "name": "VYd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYff": {
+      "__class__": "LogTocElement",
+      "ident": 333,
+      "group": "posCtl",
+      "name": "VYff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZp": {
+      "__class__": "LogTocElement",
+      "ident": 334,
+      "group": "posCtl",
+      "name": "VZp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZi": {
+      "__class__": "LogTocElement",
+      "ident": 335,
+      "group": "posCtl",
+      "name": "VZi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZd": {
+      "__class__": "LogTocElement",
+      "ident": 336,
+      "group": "posCtl",
+      "name": "VZd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZff": {
+      "__class__": "LogTocElement",
+      "ident": 337,
+      "group": "posCtl",
+      "name": "VZff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "posEstAlt": {
+    "estimatedZ": {
+      "__class__": "LogTocElement",
+      "ident": 338,
+      "group": "posEstAlt",
+      "name": "estimatedZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estVZ": {
+      "__class__": "LogTocElement",
+      "ident": 339,
+      "group": "posEstAlt",
+      "name": "estVZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velocityZ": {
+      "__class__": "LogTocElement",
+      "ident": 340,
+      "group": "posEstAlt",
+      "name": "velocityZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "range": {
+    "front": {
+      "__class__": "LogTocElement",
+      "ident": 341,
+      "group": "range",
+      "name": "front",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "back": {
+      "__class__": "LogTocElement",
+      "ident": 342,
+      "group": "range",
+      "name": "back",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "up": {
+      "__class__": "LogTocElement",
+      "ident": 343,
+      "group": "range",
+      "name": "up",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "left": {
+      "__class__": "LogTocElement",
+      "ident": 344,
+      "group": "range",
+      "name": "left",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "right": {
+      "__class__": "LogTocElement",
+      "ident": 345,
+      "group": "range",
+      "name": "right",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "zrange": {
+      "__class__": "LogTocElement",
+      "ident": 346,
+      "group": "range",
+      "name": "zrange",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "sensfusion6": {
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 347,
+      "group": "sensfusion6",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 348,
+      "group": "sensfusion6",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 349,
+      "group": "sensfusion6",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 350,
+      "group": "sensfusion6",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityX": {
+      "__class__": "LogTocElement",
+      "ident": 351,
+      "group": "sensfusion6",
+      "name": "gravityX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityY": {
+      "__class__": "LogTocElement",
+      "ident": 352,
+      "group": "sensfusion6",
+      "name": "gravityY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityZ": {
+      "__class__": "LogTocElement",
+      "ident": 353,
+      "group": "sensfusion6",
+      "name": "gravityZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accZbase": {
+      "__class__": "LogTocElement",
+      "ident": 354,
+      "group": "sensfusion6",
+      "name": "accZbase",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "isInit": {
+      "__class__": "LogTocElement",
+      "ident": 355,
+      "group": "sensfusion6",
+      "name": "isInit",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isCalibrated": {
+      "__class__": "LogTocElement",
+      "ident": 356,
+      "group": "sensfusion6",
+      "name": "isCalibrated",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "acc": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 357,
+      "group": "acc",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 358,
+      "group": "acc",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 359,
+      "group": "acc",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "baro": {
+    "asl": {
+      "__class__": "LogTocElement",
+      "ident": 360,
+      "group": "baro",
+      "name": "asl",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "temp": {
+      "__class__": "LogTocElement",
+      "ident": 361,
+      "group": "baro",
+      "name": "temp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure": {
+      "__class__": "LogTocElement",
+      "ident": 362,
+      "group": "baro",
+      "name": "pressure",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrltarget": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 363,
+      "group": "ctrltarget",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 364,
+      "group": "ctrltarget",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 365,
+      "group": "ctrltarget",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 366,
+      "group": "ctrltarget",
+      "name": "vx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 367,
+      "group": "ctrltarget",
+      "name": "vy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 368,
+      "group": "ctrltarget",
+      "name": "vz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 369,
+      "group": "ctrltarget",
+      "name": "ax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 370,
+      "group": "ctrltarget",
+      "name": "ay",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 371,
+      "group": "ctrltarget",
+      "name": "az",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 372,
+      "group": "ctrltarget",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 373,
+      "group": "ctrltarget",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 374,
+      "group": "ctrltarget",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrltargetZ": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 375,
+      "group": "ctrltargetZ",
+      "name": "x",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 376,
+      "group": "ctrltargetZ",
+      "name": "y",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 377,
+      "group": "ctrltargetZ",
+      "name": "z",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 378,
+      "group": "ctrltargetZ",
+      "name": "vx",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 379,
+      "group": "ctrltargetZ",
+      "name": "vy",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 380,
+      "group": "ctrltargetZ",
+      "name": "vz",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 381,
+      "group": "ctrltargetZ",
+      "name": "ax",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 382,
+      "group": "ctrltargetZ",
+      "name": "ay",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 383,
+      "group": "ctrltargetZ",
+      "name": "az",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "mag": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 384,
+      "group": "mag",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 385,
+      "group": "mag",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 386,
+      "group": "mag",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "stabilizer": {
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 387,
+      "group": "stabilizer",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 388,
+      "group": "stabilizer",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 389,
+      "group": "stabilizer",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "thrust": {
+      "__class__": "LogTocElement",
+      "ident": 390,
+      "group": "stabilizer",
+      "name": "thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtStab": {
+      "__class__": "LogTocElement",
+      "ident": 391,
+      "group": "stabilizer",
+      "name": "rtStab",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "intToOut": {
+      "__class__": "LogTocElement",
+      "ident": 392,
+      "group": "stabilizer",
+      "name": "intToOut",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "stateEstimate": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 393,
+      "group": "stateEstimate",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 394,
+      "group": "stateEstimate",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 395,
+      "group": "stateEstimate",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 396,
+      "group": "stateEstimate",
+      "name": "vx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 397,
+      "group": "stateEstimate",
+      "name": "vy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 398,
+      "group": "stateEstimate",
+      "name": "vz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 399,
+      "group": "stateEstimate",
+      "name": "ax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 400,
+      "group": "stateEstimate",
+      "name": "ay",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 401,
+      "group": "stateEstimate",
+      "name": "az",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 402,
+      "group": "stateEstimate",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 403,
+      "group": "stateEstimate",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 404,
+      "group": "stateEstimate",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 405,
+      "group": "stateEstimate",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 406,
+      "group": "stateEstimate",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 407,
+      "group": "stateEstimate",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 408,
+      "group": "stateEstimate",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "stateEstimateZ": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 409,
+      "group": "stateEstimateZ",
+      "name": "x",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 410,
+      "group": "stateEstimateZ",
+      "name": "y",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 411,
+      "group": "stateEstimateZ",
+      "name": "z",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 412,
+      "group": "stateEstimateZ",
+      "name": "vx",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 413,
+      "group": "stateEstimateZ",
+      "name": "vy",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 414,
+      "group": "stateEstimateZ",
+      "name": "vz",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 415,
+      "group": "stateEstimateZ",
+      "name": "ax",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 416,
+      "group": "stateEstimateZ",
+      "name": "ay",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 417,
+      "group": "stateEstimateZ",
+      "name": "az",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "quat": {
+      "__class__": "LogTocElement",
+      "ident": 418,
+      "group": "stateEstimateZ",
+      "name": "quat",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "rateRoll": {
+      "__class__": "LogTocElement",
+      "ident": 419,
+      "group": "stateEstimateZ",
+      "name": "rateRoll",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ratePitch": {
+      "__class__": "LogTocElement",
+      "ident": 420,
+      "group": "stateEstimateZ",
+      "name": "ratePitch",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "rateYaw": {
+      "__class__": "LogTocElement",
+      "ident": 421,
+      "group": "stateEstimateZ",
+      "name": "rateYaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "sys": {
+    "canfly": {
+      "__class__": "LogTocElement",
+      "ident": 422,
+      "group": "sys",
+      "name": "canfly",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isFlying": {
+      "__class__": "LogTocElement",
+      "ident": 423,
+      "group": "sys",
+      "name": "isFlying",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isTumbled": {
+      "__class__": "LogTocElement",
+      "ident": 424,
+      "group": "sys",
+      "name": "isTumbled",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "armed": {
+      "__class__": "LogTocElement",
+      "ident": 425,
+      "group": "sys",
+      "name": "armed",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0
+    }
+  },
+  "tdoaEngine": {
+    "stRx": {
+      "__class__": "LogTocElement",
+      "ident": 426,
+      "group": "tdoaEngine",
+      "name": "stRx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stEst": {
+      "__class__": "LogTocElement",
+      "ident": 427,
+      "group": "tdoaEngine",
+      "name": "stEst",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stTime": {
+      "__class__": "LogTocElement",
+      "ident": 428,
+      "group": "tdoaEngine",
+      "name": "stTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stFound": {
+      "__class__": "LogTocElement",
+      "ident": 429,
+      "group": "tdoaEngine",
+      "name": "stFound",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stCc": {
+      "__class__": "LogTocElement",
+      "ident": 430,
+      "group": "tdoaEngine",
+      "name": "stCc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stHit": {
+      "__class__": "LogTocElement",
+      "ident": 431,
+      "group": "tdoaEngine",
+      "name": "stHit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stMiss": {
+      "__class__": "LogTocElement",
+      "ident": 432,
+      "group": "tdoaEngine",
+      "name": "stMiss",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc": {
+      "__class__": "LogTocElement",
+      "ident": 433,
+      "group": "tdoaEngine",
+      "name": "cc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "tof": {
+      "__class__": "LogTocElement",
+      "ident": 434,
+      "group": "tdoaEngine",
+      "name": "tof",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "tdoa": {
+      "__class__": "LogTocElement",
+      "ident": 435,
+      "group": "tdoaEngine",
+      "name": "tdoa",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "DTR_P2P": {
+    "rx_state": {
+      "__class__": "LogTocElement",
+      "ident": 436,
+      "group": "DTR_P2P",
+      "name": "rx_state",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "tx_state": {
+      "__class__": "LogTocElement",
+      "ident": 437,
+      "group": "DTR_P2P",
+      "name": "tx_state",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "kalman_pred": {
+    "predNX": {
+      "__class__": "LogTocElement",
+      "ident": 438,
+      "group": "kalman_pred",
+      "name": "predNX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "predNY": {
+      "__class__": "LogTocElement",
+      "ident": 439,
+      "group": "kalman_pred",
+      "name": "predNY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "measNX": {
+      "__class__": "LogTocElement",
+      "ident": 440,
+      "group": "kalman_pred",
+      "name": "measNX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "measNY": {
+      "__class__": "LogTocElement",
+      "ident": 441,
+      "group": "kalman_pred",
+      "name": "measNY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "lighthouse": {
+    "validAngles": {
+      "__class__": "LogTocElement",
+      "ident": 442,
+      "group": "lighthouse",
+      "name": "validAngles",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rawAngle0x": {
+      "__class__": "LogTocElement",
+      "ident": 443,
+      "group": "lighthouse",
+      "name": "rawAngle0x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0y": {
+      "__class__": "LogTocElement",
+      "ident": 444,
+      "group": "lighthouse",
+      "name": "rawAngle0y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1x": {
+      "__class__": "LogTocElement",
+      "ident": 445,
+      "group": "lighthouse",
+      "name": "rawAngle1x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1y": {
+      "__class__": "LogTocElement",
+      "ident": 446,
+      "group": "lighthouse",
+      "name": "rawAngle1y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x": {
+      "__class__": "LogTocElement",
+      "ident": 447,
+      "group": "lighthouse",
+      "name": "angle0x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y": {
+      "__class__": "LogTocElement",
+      "ident": 448,
+      "group": "lighthouse",
+      "name": "angle0y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x": {
+      "__class__": "LogTocElement",
+      "ident": 449,
+      "group": "lighthouse",
+      "name": "angle1x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y": {
+      "__class__": "LogTocElement",
+      "ident": 450,
+      "group": "lighthouse",
+      "name": "angle1y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_1": {
+      "__class__": "LogTocElement",
+      "ident": 451,
+      "group": "lighthouse",
+      "name": "angle0x_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_1": {
+      "__class__": "LogTocElement",
+      "ident": 452,
+      "group": "lighthouse",
+      "name": "angle0y_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_1": {
+      "__class__": "LogTocElement",
+      "ident": 453,
+      "group": "lighthouse",
+      "name": "angle1x_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_1": {
+      "__class__": "LogTocElement",
+      "ident": 454,
+      "group": "lighthouse",
+      "name": "angle1y_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_2": {
+      "__class__": "LogTocElement",
+      "ident": 455,
+      "group": "lighthouse",
+      "name": "angle0x_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_2": {
+      "__class__": "LogTocElement",
+      "ident": 456,
+      "group": "lighthouse",
+      "name": "angle0y_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_2": {
+      "__class__": "LogTocElement",
+      "ident": 457,
+      "group": "lighthouse",
+      "name": "angle1x_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_2": {
+      "__class__": "LogTocElement",
+      "ident": 458,
+      "group": "lighthouse",
+      "name": "angle1y_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_3": {
+      "__class__": "LogTocElement",
+      "ident": 459,
+      "group": "lighthouse",
+      "name": "angle0x_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_3": {
+      "__class__": "LogTocElement",
+      "ident": 460,
+      "group": "lighthouse",
+      "name": "angle0y_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_3": {
+      "__class__": "LogTocElement",
+      "ident": 461,
+      "group": "lighthouse",
+      "name": "angle1x_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_3": {
+      "__class__": "LogTocElement",
+      "ident": 462,
+      "group": "lighthouse",
+      "name": "angle1y_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0xlh2": {
+      "__class__": "LogTocElement",
+      "ident": 463,
+      "group": "lighthouse",
+      "name": "rawAngle0xlh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0ylh2": {
+      "__class__": "LogTocElement",
+      "ident": 464,
+      "group": "lighthouse",
+      "name": "rawAngle0ylh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1xlh2": {
+      "__class__": "LogTocElement",
+      "ident": 465,
+      "group": "lighthouse",
+      "name": "rawAngle1xlh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1ylh2": {
+      "__class__": "LogTocElement",
+      "ident": 466,
+      "group": "lighthouse",
+      "name": "rawAngle1ylh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 467,
+      "group": "lighthouse",
+      "name": "angle0x_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 468,
+      "group": "lighthouse",
+      "name": "angle0y_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 469,
+      "group": "lighthouse",
+      "name": "angle1x_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 470,
+      "group": "lighthouse",
+      "name": "angle1y_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "width0": {
+      "__class__": "LogTocElement",
+      "ident": 471,
+      "group": "lighthouse",
+      "name": "width0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width1": {
+      "__class__": "LogTocElement",
+      "ident": 472,
+      "group": "lighthouse",
+      "name": "width1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width2": {
+      "__class__": "LogTocElement",
+      "ident": 473,
+      "group": "lighthouse",
+      "name": "width2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width3": {
+      "__class__": "LogTocElement",
+      "ident": 474,
+      "group": "lighthouse",
+      "name": "width3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "comSync": {
+      "__class__": "LogTocElement",
+      "ident": 475,
+      "group": "lighthouse",
+      "name": "comSync",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "bsAvailable": {
+      "__class__": "LogTocElement",
+      "ident": 476,
+      "group": "lighthouse",
+      "name": "bsAvailable",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsReceive": {
+      "__class__": "LogTocElement",
+      "ident": 477,
+      "group": "lighthouse",
+      "name": "bsReceive",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsActive": {
+      "__class__": "LogTocElement",
+      "ident": 478,
+      "group": "lighthouse",
+      "name": "bsActive",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalUd": {
+      "__class__": "LogTocElement",
+      "ident": 479,
+      "group": "lighthouse",
+      "name": "bsCalUd",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalCon": {
+      "__class__": "LogTocElement",
+      "ident": 480,
+      "group": "lighthouse",
+      "name": "bsCalCon",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "status": {
+      "__class__": "LogTocElement",
+      "ident": 481,
+      "group": "lighthouse",
+      "name": "status",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "posRt": {
+      "__class__": "LogTocElement",
+      "ident": 482,
+      "group": "lighthouse",
+      "name": "posRt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estBs0Rt": {
+      "__class__": "LogTocElement",
+      "ident": 483,
+      "group": "lighthouse",
+      "name": "estBs0Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estBs1Rt": {
+      "__class__": "LogTocElement",
+      "ident": 484,
+      "group": "lighthouse",
+      "name": "estBs1Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 485,
+      "group": "lighthouse",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 486,
+      "group": "lighthouse",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 487,
+      "group": "lighthouse",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "delta": {
+      "__class__": "LogTocElement",
+      "ident": 488,
+      "group": "lighthouse",
+      "name": "delta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bsGeoVal": {
+      "__class__": "LogTocElement",
+      "ident": 489,
+      "group": "lighthouse",
+      "name": "bsGeoVal",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalVal": {
+      "__class__": "LogTocElement",
+      "ident": 490,
+      "group": "lighthouse",
+      "name": "bsCalVal",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "disProb": {
+      "__class__": "LogTocElement",
+      "ident": 491,
+      "group": "lighthouse",
+      "name": "disProb",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  }
+}
\ No newline at end of file
diff --git a/crazyflie_demos/cache/12B17A17.json b/crazyflie_demos/cache/12B17A17.json
new file mode 100644
index 0000000000000000000000000000000000000000..6f4322fb6c0c7d8bee24802681f137129e8edcdc
--- /dev/null
+++ b/crazyflie_demos/cache/12B17A17.json
@@ -0,0 +1,4517 @@
+{
+  "activeMarker": {
+    "btSns": {
+      "__class__": "LogTocElement",
+      "ident": 0,
+      "group": "activeMarker",
+      "name": "btSns",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "i2cOk": {
+      "__class__": "LogTocElement",
+      "ident": 1,
+      "group": "activeMarker",
+      "name": "i2cOk",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "motion": {
+    "motion": {
+      "__class__": "LogTocElement",
+      "ident": 2,
+      "group": "motion",
+      "name": "motion",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "deltaX": {
+      "__class__": "LogTocElement",
+      "ident": 3,
+      "group": "motion",
+      "name": "deltaX",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "deltaY": {
+      "__class__": "LogTocElement",
+      "ident": 4,
+      "group": "motion",
+      "name": "deltaY",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "shutter": {
+      "__class__": "LogTocElement",
+      "ident": 5,
+      "group": "motion",
+      "name": "shutter",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "maxRaw": {
+      "__class__": "LogTocElement",
+      "ident": 6,
+      "group": "motion",
+      "name": "maxRaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "minRaw": {
+      "__class__": "LogTocElement",
+      "ident": 7,
+      "group": "motion",
+      "name": "minRaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "Rawsum": {
+      "__class__": "LogTocElement",
+      "ident": 8,
+      "group": "motion",
+      "name": "Rawsum",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "outlierCount": {
+      "__class__": "LogTocElement",
+      "ident": 9,
+      "group": "motion",
+      "name": "outlierCount",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "squal": {
+      "__class__": "LogTocElement",
+      "ident": 10,
+      "group": "motion",
+      "name": "squal",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "std": {
+      "__class__": "LogTocElement",
+      "ident": 11,
+      "group": "motion",
+      "name": "std",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ring": {
+    "fadeTime": {
+      "__class__": "LogTocElement",
+      "ident": 12,
+      "group": "ring",
+      "name": "fadeTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "loco": {
+    "mode": {
+      "__class__": "LogTocElement",
+      "ident": 13,
+      "group": "loco",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "spiWr": {
+      "__class__": "LogTocElement",
+      "ident": 14,
+      "group": "loco",
+      "name": "spiWr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "spiRe": {
+      "__class__": "LogTocElement",
+      "ident": 15,
+      "group": "loco",
+      "name": "spiRe",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ranging": {
+    "state": {
+      "__class__": "LogTocElement",
+      "ident": 16,
+      "group": "ranging",
+      "name": "state",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "distance0": {
+      "__class__": "LogTocElement",
+      "ident": 17,
+      "group": "ranging",
+      "name": "distance0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance1": {
+      "__class__": "LogTocElement",
+      "ident": 18,
+      "group": "ranging",
+      "name": "distance1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance2": {
+      "__class__": "LogTocElement",
+      "ident": 19,
+      "group": "ranging",
+      "name": "distance2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance3": {
+      "__class__": "LogTocElement",
+      "ident": 20,
+      "group": "ranging",
+      "name": "distance3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance4": {
+      "__class__": "LogTocElement",
+      "ident": 21,
+      "group": "ranging",
+      "name": "distance4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance5": {
+      "__class__": "LogTocElement",
+      "ident": 22,
+      "group": "ranging",
+      "name": "distance5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance6": {
+      "__class__": "LogTocElement",
+      "ident": 23,
+      "group": "ranging",
+      "name": "distance6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance7": {
+      "__class__": "LogTocElement",
+      "ident": 24,
+      "group": "ranging",
+      "name": "distance7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure0": {
+      "__class__": "LogTocElement",
+      "ident": 25,
+      "group": "ranging",
+      "name": "pressure0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure1": {
+      "__class__": "LogTocElement",
+      "ident": 26,
+      "group": "ranging",
+      "name": "pressure1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure2": {
+      "__class__": "LogTocElement",
+      "ident": 27,
+      "group": "ranging",
+      "name": "pressure2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure3": {
+      "__class__": "LogTocElement",
+      "ident": 28,
+      "group": "ranging",
+      "name": "pressure3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure4": {
+      "__class__": "LogTocElement",
+      "ident": 29,
+      "group": "ranging",
+      "name": "pressure4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure5": {
+      "__class__": "LogTocElement",
+      "ident": 30,
+      "group": "ranging",
+      "name": "pressure5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure6": {
+      "__class__": "LogTocElement",
+      "ident": 31,
+      "group": "ranging",
+      "name": "pressure6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure7": {
+      "__class__": "LogTocElement",
+      "ident": 32,
+      "group": "ranging",
+      "name": "pressure7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "tdoa2": {
+    "d7-0": {
+      "__class__": "LogTocElement",
+      "ident": 33,
+      "group": "tdoa2",
+      "name": "d7-0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d0-1": {
+      "__class__": "LogTocElement",
+      "ident": 34,
+      "group": "tdoa2",
+      "name": "d0-1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d1-2": {
+      "__class__": "LogTocElement",
+      "ident": 35,
+      "group": "tdoa2",
+      "name": "d1-2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d2-3": {
+      "__class__": "LogTocElement",
+      "ident": 36,
+      "group": "tdoa2",
+      "name": "d2-3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d3-4": {
+      "__class__": "LogTocElement",
+      "ident": 37,
+      "group": "tdoa2",
+      "name": "d3-4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d4-5": {
+      "__class__": "LogTocElement",
+      "ident": 38,
+      "group": "tdoa2",
+      "name": "d4-5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d5-6": {
+      "__class__": "LogTocElement",
+      "ident": 39,
+      "group": "tdoa2",
+      "name": "d5-6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d6-7": {
+      "__class__": "LogTocElement",
+      "ident": 40,
+      "group": "tdoa2",
+      "name": "d6-7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc0": {
+      "__class__": "LogTocElement",
+      "ident": 41,
+      "group": "tdoa2",
+      "name": "cc0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc1": {
+      "__class__": "LogTocElement",
+      "ident": 42,
+      "group": "tdoa2",
+      "name": "cc1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc2": {
+      "__class__": "LogTocElement",
+      "ident": 43,
+      "group": "tdoa2",
+      "name": "cc2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc3": {
+      "__class__": "LogTocElement",
+      "ident": 44,
+      "group": "tdoa2",
+      "name": "cc3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc4": {
+      "__class__": "LogTocElement",
+      "ident": 45,
+      "group": "tdoa2",
+      "name": "cc4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc5": {
+      "__class__": "LogTocElement",
+      "ident": 46,
+      "group": "tdoa2",
+      "name": "cc5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc6": {
+      "__class__": "LogTocElement",
+      "ident": 47,
+      "group": "tdoa2",
+      "name": "cc6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc7": {
+      "__class__": "LogTocElement",
+      "ident": 48,
+      "group": "tdoa2",
+      "name": "cc7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "dist7-0": {
+      "__class__": "LogTocElement",
+      "ident": 49,
+      "group": "tdoa2",
+      "name": "dist7-0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist0-1": {
+      "__class__": "LogTocElement",
+      "ident": 50,
+      "group": "tdoa2",
+      "name": "dist0-1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist1-2": {
+      "__class__": "LogTocElement",
+      "ident": 51,
+      "group": "tdoa2",
+      "name": "dist1-2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist2-3": {
+      "__class__": "LogTocElement",
+      "ident": 52,
+      "group": "tdoa2",
+      "name": "dist2-3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist3-4": {
+      "__class__": "LogTocElement",
+      "ident": 53,
+      "group": "tdoa2",
+      "name": "dist3-4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist4-5": {
+      "__class__": "LogTocElement",
+      "ident": 54,
+      "group": "tdoa2",
+      "name": "dist4-5",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist5-6": {
+      "__class__": "LogTocElement",
+      "ident": 55,
+      "group": "tdoa2",
+      "name": "dist5-6",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist6-7": {
+      "__class__": "LogTocElement",
+      "ident": 56,
+      "group": "tdoa2",
+      "name": "dist6-7",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "twr": {
+    "rangingSuccessRate0": {
+      "__class__": "LogTocElement",
+      "ident": 57,
+      "group": "twr",
+      "name": "rangingSuccessRate0",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec0": {
+      "__class__": "LogTocElement",
+      "ident": 58,
+      "group": "twr",
+      "name": "rangingPerSec0",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate1": {
+      "__class__": "LogTocElement",
+      "ident": 59,
+      "group": "twr",
+      "name": "rangingSuccessRate1",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec1": {
+      "__class__": "LogTocElement",
+      "ident": 60,
+      "group": "twr",
+      "name": "rangingPerSec1",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate2": {
+      "__class__": "LogTocElement",
+      "ident": 61,
+      "group": "twr",
+      "name": "rangingSuccessRate2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec2": {
+      "__class__": "LogTocElement",
+      "ident": 62,
+      "group": "twr",
+      "name": "rangingPerSec2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate3": {
+      "__class__": "LogTocElement",
+      "ident": 63,
+      "group": "twr",
+      "name": "rangingSuccessRate3",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec3": {
+      "__class__": "LogTocElement",
+      "ident": 64,
+      "group": "twr",
+      "name": "rangingPerSec3",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate4": {
+      "__class__": "LogTocElement",
+      "ident": 65,
+      "group": "twr",
+      "name": "rangingSuccessRate4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec4": {
+      "__class__": "LogTocElement",
+      "ident": 66,
+      "group": "twr",
+      "name": "rangingPerSec4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate5": {
+      "__class__": "LogTocElement",
+      "ident": 67,
+      "group": "twr",
+      "name": "rangingSuccessRate5",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec5": {
+      "__class__": "LogTocElement",
+      "ident": 68,
+      "group": "twr",
+      "name": "rangingPerSec5",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "oa": {
+    "front": {
+      "__class__": "LogTocElement",
+      "ident": 69,
+      "group": "oa",
+      "name": "front",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "back": {
+      "__class__": "LogTocElement",
+      "ident": 70,
+      "group": "oa",
+      "name": "back",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "up": {
+      "__class__": "LogTocElement",
+      "ident": 71,
+      "group": "oa",
+      "name": "up",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "left": {
+      "__class__": "LogTocElement",
+      "ident": 72,
+      "group": "oa",
+      "name": "left",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "right": {
+      "__class__": "LogTocElement",
+      "ident": 73,
+      "group": "oa",
+      "name": "right",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "usd": {
+    "spiWrBps": {
+      "__class__": "LogTocElement",
+      "ident": 74,
+      "group": "usd",
+      "name": "spiWrBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "spiReBps": {
+      "__class__": "LogTocElement",
+      "ident": 75,
+      "group": "usd",
+      "name": "spiReBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "fatWrBps": {
+      "__class__": "LogTocElement",
+      "ident": 76,
+      "group": "usd",
+      "name": "fatWrBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "motor": {
+    "m1": {
+      "__class__": "LogTocElement",
+      "ident": 77,
+      "group": "motor",
+      "name": "m1",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m2": {
+      "__class__": "LogTocElement",
+      "ident": 78,
+      "group": "motor",
+      "name": "m2",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m3": {
+      "__class__": "LogTocElement",
+      "ident": 79,
+      "group": "motor",
+      "name": "m3",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m4": {
+      "__class__": "LogTocElement",
+      "ident": 80,
+      "group": "motor",
+      "name": "m4",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m1req": {
+      "__class__": "LogTocElement",
+      "ident": 81,
+      "group": "motor",
+      "name": "m1req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "m2req": {
+      "__class__": "LogTocElement",
+      "ident": 82,
+      "group": "motor",
+      "name": "m2req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "m3req": {
+      "__class__": "LogTocElement",
+      "ident": 83,
+      "group": "motor",
+      "name": "m3req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "m4req": {
+      "__class__": "LogTocElement",
+      "ident": 84,
+      "group": "motor",
+      "name": "m4req",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    }
+  },
+  "pm": {
+    "vbat": {
+      "__class__": "LogTocElement",
+      "ident": 85,
+      "group": "pm",
+      "name": "vbat",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vbatMV": {
+      "__class__": "LogTocElement",
+      "ident": 86,
+      "group": "pm",
+      "name": "vbatMV",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "extVbat": {
+      "__class__": "LogTocElement",
+      "ident": 87,
+      "group": "pm",
+      "name": "extVbat",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "extVbatMV": {
+      "__class__": "LogTocElement",
+      "ident": 88,
+      "group": "pm",
+      "name": "extVbatMV",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "extCurr": {
+      "__class__": "LogTocElement",
+      "ident": 89,
+      "group": "pm",
+      "name": "extCurr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "chargeCurrent": {
+      "__class__": "LogTocElement",
+      "ident": 90,
+      "group": "pm",
+      "name": "chargeCurrent",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "state": {
+      "__class__": "LogTocElement",
+      "ident": 91,
+      "group": "pm",
+      "name": "state",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0
+    },
+    "batteryLevel": {
+      "__class__": "LogTocElement",
+      "ident": 92,
+      "group": "pm",
+      "name": "batteryLevel",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "radio": {
+    "rssi": {
+      "__class__": "LogTocElement",
+      "ident": 93,
+      "group": "radio",
+      "name": "rssi",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isConnected": {
+      "__class__": "LogTocElement",
+      "ident": 94,
+      "group": "radio",
+      "name": "isConnected",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "gyro": {
+    "xRaw": {
+      "__class__": "LogTocElement",
+      "ident": 95,
+      "group": "gyro",
+      "name": "xRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "yRaw": {
+      "__class__": "LogTocElement",
+      "ident": 96,
+      "group": "gyro",
+      "name": "yRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "zRaw": {
+      "__class__": "LogTocElement",
+      "ident": 97,
+      "group": "gyro",
+      "name": "zRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "xVariance": {
+      "__class__": "LogTocElement",
+      "ident": 98,
+      "group": "gyro",
+      "name": "xVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yVariance": {
+      "__class__": "LogTocElement",
+      "ident": 99,
+      "group": "gyro",
+      "name": "yVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zVariance": {
+      "__class__": "LogTocElement",
+      "ident": 100,
+      "group": "gyro",
+      "name": "zVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 101,
+      "group": "gyro",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 102,
+      "group": "gyro",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 103,
+      "group": "gyro",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "pid_attitude": {
+    "roll_outP": {
+      "__class__": "LogTocElement",
+      "ident": 104,
+      "group": "pid_attitude",
+      "name": "roll_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outI": {
+      "__class__": "LogTocElement",
+      "ident": 105,
+      "group": "pid_attitude",
+      "name": "roll_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outD": {
+      "__class__": "LogTocElement",
+      "ident": 106,
+      "group": "pid_attitude",
+      "name": "roll_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 107,
+      "group": "pid_attitude",
+      "name": "roll_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outP": {
+      "__class__": "LogTocElement",
+      "ident": 108,
+      "group": "pid_attitude",
+      "name": "pitch_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outI": {
+      "__class__": "LogTocElement",
+      "ident": 109,
+      "group": "pid_attitude",
+      "name": "pitch_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outD": {
+      "__class__": "LogTocElement",
+      "ident": 110,
+      "group": "pid_attitude",
+      "name": "pitch_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 111,
+      "group": "pid_attitude",
+      "name": "pitch_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outP": {
+      "__class__": "LogTocElement",
+      "ident": 112,
+      "group": "pid_attitude",
+      "name": "yaw_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outI": {
+      "__class__": "LogTocElement",
+      "ident": 113,
+      "group": "pid_attitude",
+      "name": "yaw_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outD": {
+      "__class__": "LogTocElement",
+      "ident": 114,
+      "group": "pid_attitude",
+      "name": "yaw_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 115,
+      "group": "pid_attitude",
+      "name": "yaw_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "pid_rate": {
+    "roll_outP": {
+      "__class__": "LogTocElement",
+      "ident": 116,
+      "group": "pid_rate",
+      "name": "roll_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outI": {
+      "__class__": "LogTocElement",
+      "ident": 117,
+      "group": "pid_rate",
+      "name": "roll_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outD": {
+      "__class__": "LogTocElement",
+      "ident": 118,
+      "group": "pid_rate",
+      "name": "roll_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 119,
+      "group": "pid_rate",
+      "name": "roll_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outP": {
+      "__class__": "LogTocElement",
+      "ident": 120,
+      "group": "pid_rate",
+      "name": "pitch_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outI": {
+      "__class__": "LogTocElement",
+      "ident": 121,
+      "group": "pid_rate",
+      "name": "pitch_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outD": {
+      "__class__": "LogTocElement",
+      "ident": 122,
+      "group": "pid_rate",
+      "name": "pitch_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 123,
+      "group": "pid_rate",
+      "name": "pitch_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outP": {
+      "__class__": "LogTocElement",
+      "ident": 124,
+      "group": "pid_rate",
+      "name": "yaw_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outI": {
+      "__class__": "LogTocElement",
+      "ident": 125,
+      "group": "pid_rate",
+      "name": "yaw_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outD": {
+      "__class__": "LogTocElement",
+      "ident": 126,
+      "group": "pid_rate",
+      "name": "yaw_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outFF": {
+      "__class__": "LogTocElement",
+      "ident": 127,
+      "group": "pid_rate",
+      "name": "yaw_outFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "colAv": {
+    "latency": {
+      "__class__": "LogTocElement",
+      "ident": 128,
+      "group": "colAv",
+      "name": "latency",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "ctrlINDI": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 129,
+      "group": "ctrlINDI",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 130,
+      "group": "ctrlINDI",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 131,
+      "group": "ctrlINDI",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 132,
+      "group": "ctrlINDI",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 133,
+      "group": "ctrlINDI",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 134,
+      "group": "ctrlINDI",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 135,
+      "group": "ctrlINDI",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_p": {
+      "__class__": "LogTocElement",
+      "ident": 136,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_q": {
+      "__class__": "LogTocElement",
+      "ident": 137,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_r": {
+      "__class__": "LogTocElement",
+      "ident": 138,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_p": {
+      "__class__": "LogTocElement",
+      "ident": 139,
+      "group": "ctrlINDI",
+      "name": "du_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_q": {
+      "__class__": "LogTocElement",
+      "ident": 140,
+      "group": "ctrlINDI",
+      "name": "du_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_r": {
+      "__class__": "LogTocElement",
+      "ident": 141,
+      "group": "ctrlINDI",
+      "name": "du_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_p": {
+      "__class__": "LogTocElement",
+      "ident": 142,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_q": {
+      "__class__": "LogTocElement",
+      "ident": 143,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_r": {
+      "__class__": "LogTocElement",
+      "ident": 144,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[0]": {
+      "__class__": "LogTocElement",
+      "ident": 145,
+      "group": "ctrlINDI",
+      "name": "rate_d[0]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[1]": {
+      "__class__": "LogTocElement",
+      "ident": 146,
+      "group": "ctrlINDI",
+      "name": "rate_d[1]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[2]": {
+      "__class__": "LogTocElement",
+      "ident": 147,
+      "group": "ctrlINDI",
+      "name": "rate_d[2]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_p": {
+      "__class__": "LogTocElement",
+      "ident": 148,
+      "group": "ctrlINDI",
+      "name": "uf_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_q": {
+      "__class__": "LogTocElement",
+      "ident": 149,
+      "group": "ctrlINDI",
+      "name": "uf_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_r": {
+      "__class__": "LogTocElement",
+      "ident": 150,
+      "group": "ctrlINDI",
+      "name": "uf_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_p": {
+      "__class__": "LogTocElement",
+      "ident": 151,
+      "group": "ctrlINDI",
+      "name": "Omega_f_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_q": {
+      "__class__": "LogTocElement",
+      "ident": 152,
+      "group": "ctrlINDI",
+      "name": "Omega_f_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_r": {
+      "__class__": "LogTocElement",
+      "ident": 153,
+      "group": "ctrlINDI",
+      "name": "Omega_f_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_p": {
+      "__class__": "LogTocElement",
+      "ident": 154,
+      "group": "ctrlINDI",
+      "name": "n_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_q": {
+      "__class__": "LogTocElement",
+      "ident": 155,
+      "group": "ctrlINDI",
+      "name": "n_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_r": {
+      "__class__": "LogTocElement",
+      "ident": 156,
+      "group": "ctrlINDI",
+      "name": "n_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrlMel": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 157,
+      "group": "ctrlMel",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 158,
+      "group": "ctrlMel",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 159,
+      "group": "ctrlMel",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 160,
+      "group": "ctrlMel",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 161,
+      "group": "ctrlMel",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 162,
+      "group": "ctrlMel",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 163,
+      "group": "ctrlMel",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accelz": {
+      "__class__": "LogTocElement",
+      "ident": 164,
+      "group": "ctrlMel",
+      "name": "accelz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdx": {
+      "__class__": "LogTocElement",
+      "ident": 165,
+      "group": "ctrlMel",
+      "name": "zdx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdy": {
+      "__class__": "LogTocElement",
+      "ident": 166,
+      "group": "ctrlMel",
+      "name": "zdy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdz": {
+      "__class__": "LogTocElement",
+      "ident": 167,
+      "group": "ctrlMel",
+      "name": "zdz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_x": {
+      "__class__": "LogTocElement",
+      "ident": 168,
+      "group": "ctrlMel",
+      "name": "i_err_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_y": {
+      "__class__": "LogTocElement",
+      "ident": 169,
+      "group": "ctrlMel",
+      "name": "i_err_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_z": {
+      "__class__": "LogTocElement",
+      "ident": 170,
+      "group": "ctrlMel",
+      "name": "i_err_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "controller": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 171,
+      "group": "controller",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 172,
+      "group": "controller",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 173,
+      "group": "controller",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 174,
+      "group": "controller",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 175,
+      "group": "controller",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 176,
+      "group": "controller",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 177,
+      "group": "controller",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accelz": {
+      "__class__": "LogTocElement",
+      "ident": 178,
+      "group": "controller",
+      "name": "accelz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "actuatorThrust": {
+      "__class__": "LogTocElement",
+      "ident": 179,
+      "group": "controller",
+      "name": "actuatorThrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 180,
+      "group": "controller",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 181,
+      "group": "controller",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 182,
+      "group": "controller",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rollRate": {
+      "__class__": "LogTocElement",
+      "ident": 183,
+      "group": "controller",
+      "name": "rollRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitchRate": {
+      "__class__": "LogTocElement",
+      "ident": 184,
+      "group": "controller",
+      "name": "pitchRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yawRate": {
+      "__class__": "LogTocElement",
+      "ident": 185,
+      "group": "controller",
+      "name": "yawRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ctr_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 186,
+      "group": "controller",
+      "name": "ctr_yaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "ext_pos": {
+    "X": {
+      "__class__": "LogTocElement",
+      "ident": 187,
+      "group": "ext_pos",
+      "name": "X",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Y": {
+      "__class__": "LogTocElement",
+      "ident": 188,
+      "group": "ext_pos",
+      "name": "Y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Z": {
+      "__class__": "LogTocElement",
+      "ident": 189,
+      "group": "ext_pos",
+      "name": "Z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "locSrv": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 190,
+      "group": "locSrv",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 191,
+      "group": "locSrv",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 192,
+      "group": "locSrv",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 193,
+      "group": "locSrv",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 194,
+      "group": "locSrv",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 195,
+      "group": "locSrv",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 196,
+      "group": "locSrv",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "locSrvZ": {
+    "tick": {
+      "__class__": "LogTocElement",
+      "ident": 197,
+      "group": "locSrvZ",
+      "name": "tick",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "crtp": {
+    "rxRate": {
+      "__class__": "LogTocElement",
+      "ident": 198,
+      "group": "crtp",
+      "name": "rxRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "txRate": {
+      "__class__": "LogTocElement",
+      "ident": 199,
+      "group": "crtp",
+      "name": "txRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "kalman": {
+    "stateX": {
+      "__class__": "LogTocElement",
+      "ident": 200,
+      "group": "kalman",
+      "name": "stateX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateY": {
+      "__class__": "LogTocElement",
+      "ident": 201,
+      "group": "kalman",
+      "name": "stateY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateZ": {
+      "__class__": "LogTocElement",
+      "ident": 202,
+      "group": "kalman",
+      "name": "stateZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePX": {
+      "__class__": "LogTocElement",
+      "ident": 203,
+      "group": "kalman",
+      "name": "statePX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePY": {
+      "__class__": "LogTocElement",
+      "ident": 204,
+      "group": "kalman",
+      "name": "statePY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePZ": {
+      "__class__": "LogTocElement",
+      "ident": 205,
+      "group": "kalman",
+      "name": "statePZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD0": {
+      "__class__": "LogTocElement",
+      "ident": 206,
+      "group": "kalman",
+      "name": "stateD0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD1": {
+      "__class__": "LogTocElement",
+      "ident": 207,
+      "group": "kalman",
+      "name": "stateD1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD2": {
+      "__class__": "LogTocElement",
+      "ident": 208,
+      "group": "kalman",
+      "name": "stateD2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varX": {
+      "__class__": "LogTocElement",
+      "ident": 209,
+      "group": "kalman",
+      "name": "varX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varY": {
+      "__class__": "LogTocElement",
+      "ident": 210,
+      "group": "kalman",
+      "name": "varY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varZ": {
+      "__class__": "LogTocElement",
+      "ident": 211,
+      "group": "kalman",
+      "name": "varZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPX": {
+      "__class__": "LogTocElement",
+      "ident": 212,
+      "group": "kalman",
+      "name": "varPX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPY": {
+      "__class__": "LogTocElement",
+      "ident": 213,
+      "group": "kalman",
+      "name": "varPY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPZ": {
+      "__class__": "LogTocElement",
+      "ident": 214,
+      "group": "kalman",
+      "name": "varPZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD0": {
+      "__class__": "LogTocElement",
+      "ident": 215,
+      "group": "kalman",
+      "name": "varD0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD1": {
+      "__class__": "LogTocElement",
+      "ident": 216,
+      "group": "kalman",
+      "name": "varD1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD2": {
+      "__class__": "LogTocElement",
+      "ident": 217,
+      "group": "kalman",
+      "name": "varD2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q0": {
+      "__class__": "LogTocElement",
+      "ident": 218,
+      "group": "kalman",
+      "name": "q0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q1": {
+      "__class__": "LogTocElement",
+      "ident": 219,
+      "group": "kalman",
+      "name": "q1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q2": {
+      "__class__": "LogTocElement",
+      "ident": 220,
+      "group": "kalman",
+      "name": "q2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q3": {
+      "__class__": "LogTocElement",
+      "ident": 221,
+      "group": "kalman",
+      "name": "q3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtUpdate": {
+      "__class__": "LogTocElement",
+      "ident": 222,
+      "group": "kalman",
+      "name": "rtUpdate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtPred": {
+      "__class__": "LogTocElement",
+      "ident": 223,
+      "group": "kalman",
+      "name": "rtPred",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtFinal": {
+      "__class__": "LogTocElement",
+      "ident": 224,
+      "group": "kalman",
+      "name": "rtFinal",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "outlierf": {
+    "lhWin": {
+      "__class__": "LogTocElement",
+      "ident": 225,
+      "group": "outlierf",
+      "name": "lhWin",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket0": {
+      "__class__": "LogTocElement",
+      "ident": 226,
+      "group": "outlierf",
+      "name": "bucket0",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket1": {
+      "__class__": "LogTocElement",
+      "ident": 227,
+      "group": "outlierf",
+      "name": "bucket1",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket2": {
+      "__class__": "LogTocElement",
+      "ident": 228,
+      "group": "outlierf",
+      "name": "bucket2",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket3": {
+      "__class__": "LogTocElement",
+      "ident": 229,
+      "group": "outlierf",
+      "name": "bucket3",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket4": {
+      "__class__": "LogTocElement",
+      "ident": 230,
+      "group": "outlierf",
+      "name": "bucket4",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "accLev": {
+      "__class__": "LogTocElement",
+      "ident": 231,
+      "group": "outlierf",
+      "name": "accLev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "errD": {
+      "__class__": "LogTocElement",
+      "ident": 232,
+      "group": "outlierf",
+      "name": "errD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "estimator": {
+    "rtApnd": {
+      "__class__": "LogTocElement",
+      "ident": 233,
+      "group": "estimator",
+      "name": "rtApnd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtRej": {
+      "__class__": "LogTocElement",
+      "ident": 234,
+      "group": "estimator",
+      "name": "rtRej",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "extrx": {
+    "thrust": {
+      "__class__": "LogTocElement",
+      "ident": 235,
+      "group": "extrx",
+      "name": "thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 236,
+      "group": "extrx",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 237,
+      "group": "extrx",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rollRate": {
+      "__class__": "LogTocElement",
+      "ident": 238,
+      "group": "extrx",
+      "name": "rollRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitchRate": {
+      "__class__": "LogTocElement",
+      "ident": 239,
+      "group": "extrx",
+      "name": "pitchRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yawRate": {
+      "__class__": "LogTocElement",
+      "ident": 240,
+      "group": "extrx",
+      "name": "yawRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zVel": {
+      "__class__": "LogTocElement",
+      "ident": 241,
+      "group": "extrx",
+      "name": "zVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "AltHold": {
+      "__class__": "LogTocElement",
+      "ident": 242,
+      "group": "extrx",
+      "name": "AltHold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "Arm": {
+      "__class__": "LogTocElement",
+      "ident": 243,
+      "group": "extrx",
+      "name": "Arm",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "extrx_raw": {
+    "ch0": {
+      "__class__": "LogTocElement",
+      "ident": 244,
+      "group": "extrx_raw",
+      "name": "ch0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch1": {
+      "__class__": "LogTocElement",
+      "ident": 245,
+      "group": "extrx_raw",
+      "name": "ch1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch2": {
+      "__class__": "LogTocElement",
+      "ident": 246,
+      "group": "extrx_raw",
+      "name": "ch2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch3": {
+      "__class__": "LogTocElement",
+      "ident": 247,
+      "group": "extrx_raw",
+      "name": "ch3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch4": {
+      "__class__": "LogTocElement",
+      "ident": 248,
+      "group": "extrx_raw",
+      "name": "ch4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch5": {
+      "__class__": "LogTocElement",
+      "ident": 249,
+      "group": "extrx_raw",
+      "name": "ch5",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch6": {
+      "__class__": "LogTocElement",
+      "ident": 250,
+      "group": "extrx_raw",
+      "name": "ch6",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch7": {
+      "__class__": "LogTocElement",
+      "ident": 251,
+      "group": "extrx_raw",
+      "name": "ch7",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "health": {
+    "motorVarXM1": {
+      "__class__": "LogTocElement",
+      "ident": 252,
+      "group": "health",
+      "name": "motorVarXM1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM1": {
+      "__class__": "LogTocElement",
+      "ident": 253,
+      "group": "health",
+      "name": "motorVarYM1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM2": {
+      "__class__": "LogTocElement",
+      "ident": 254,
+      "group": "health",
+      "name": "motorVarXM2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM2": {
+      "__class__": "LogTocElement",
+      "ident": 255,
+      "group": "health",
+      "name": "motorVarYM2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM3": {
+      "__class__": "LogTocElement",
+      "ident": 256,
+      "group": "health",
+      "name": "motorVarXM3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM3": {
+      "__class__": "LogTocElement",
+      "ident": 257,
+      "group": "health",
+      "name": "motorVarYM3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM4": {
+      "__class__": "LogTocElement",
+      "ident": 258,
+      "group": "health",
+      "name": "motorVarXM4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM4": {
+      "__class__": "LogTocElement",
+      "ident": 259,
+      "group": "health",
+      "name": "motorVarYM4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorPass": {
+      "__class__": "LogTocElement",
+      "ident": 260,
+      "group": "health",
+      "name": "motorPass",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "batterySag": {
+      "__class__": "LogTocElement",
+      "ident": 261,
+      "group": "health",
+      "name": "batterySag",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "batteryPass": {
+      "__class__": "LogTocElement",
+      "ident": 262,
+      "group": "health",
+      "name": "batteryPass",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "motorTestCount": {
+      "__class__": "LogTocElement",
+      "ident": 263,
+      "group": "health",
+      "name": "motorTestCount",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "memTst": {
+    "errCntW": {
+      "__class__": "LogTocElement",
+      "ident": 264,
+      "group": "memTst",
+      "name": "errCntW",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "posCtrlIndi": {
+    "posRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 265,
+      "group": "posCtrlIndi",
+      "name": "posRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "posRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 266,
+      "group": "posCtrlIndi",
+      "name": "posRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "posRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 267,
+      "group": "posCtrlIndi",
+      "name": "posRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_x": {
+      "__class__": "LogTocElement",
+      "ident": 268,
+      "group": "posCtrlIndi",
+      "name": "velS_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_y": {
+      "__class__": "LogTocElement",
+      "ident": 269,
+      "group": "posCtrlIndi",
+      "name": "velS_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_z": {
+      "__class__": "LogTocElement",
+      "ident": 270,
+      "group": "posCtrlIndi",
+      "name": "velS_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 271,
+      "group": "posCtrlIndi",
+      "name": "velRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 272,
+      "group": "posCtrlIndi",
+      "name": "velRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 273,
+      "group": "posCtrlIndi",
+      "name": "velRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_roll": {
+      "__class__": "LogTocElement",
+      "ident": 274,
+      "group": "posCtrlIndi",
+      "name": "angS_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 275,
+      "group": "posCtrlIndi",
+      "name": "angS_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 276,
+      "group": "posCtrlIndi",
+      "name": "angS_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_roll": {
+      "__class__": "LogTocElement",
+      "ident": 277,
+      "group": "posCtrlIndi",
+      "name": "angF_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 278,
+      "group": "posCtrlIndi",
+      "name": "angF_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 279,
+      "group": "posCtrlIndi",
+      "name": "angF_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 280,
+      "group": "posCtrlIndi",
+      "name": "accRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 281,
+      "group": "posCtrlIndi",
+      "name": "accRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 282,
+      "group": "posCtrlIndi",
+      "name": "accRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_x": {
+      "__class__": "LogTocElement",
+      "ident": 283,
+      "group": "posCtrlIndi",
+      "name": "accS_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_y": {
+      "__class__": "LogTocElement",
+      "ident": 284,
+      "group": "posCtrlIndi",
+      "name": "accS_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_z": {
+      "__class__": "LogTocElement",
+      "ident": 285,
+      "group": "posCtrlIndi",
+      "name": "accS_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_x": {
+      "__class__": "LogTocElement",
+      "ident": 286,
+      "group": "posCtrlIndi",
+      "name": "accF_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_y": {
+      "__class__": "LogTocElement",
+      "ident": 287,
+      "group": "posCtrlIndi",
+      "name": "accF_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_z": {
+      "__class__": "LogTocElement",
+      "ident": 288,
+      "group": "posCtrlIndi",
+      "name": "accF_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_x": {
+      "__class__": "LogTocElement",
+      "ident": 289,
+      "group": "posCtrlIndi",
+      "name": "accFT_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_y": {
+      "__class__": "LogTocElement",
+      "ident": 290,
+      "group": "posCtrlIndi",
+      "name": "accFT_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_z": {
+      "__class__": "LogTocElement",
+      "ident": 291,
+      "group": "posCtrlIndi",
+      "name": "accFT_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_x": {
+      "__class__": "LogTocElement",
+      "ident": 292,
+      "group": "posCtrlIndi",
+      "name": "accErr_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_y": {
+      "__class__": "LogTocElement",
+      "ident": 293,
+      "group": "posCtrlIndi",
+      "name": "accErr_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_z": {
+      "__class__": "LogTocElement",
+      "ident": 294,
+      "group": "posCtrlIndi",
+      "name": "accErr_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "phi_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 295,
+      "group": "posCtrlIndi",
+      "name": "phi_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "theta_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 296,
+      "group": "posCtrlIndi",
+      "name": "theta_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 297,
+      "group": "posCtrlIndi",
+      "name": "T_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_inner": {
+      "__class__": "LogTocElement",
+      "ident": 298,
+      "group": "posCtrlIndi",
+      "name": "T_inner",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_inner_f": {
+      "__class__": "LogTocElement",
+      "ident": 299,
+      "group": "posCtrlIndi",
+      "name": "T_inner_f",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_incremented": {
+      "__class__": "LogTocElement",
+      "ident": 300,
+      "group": "posCtrlIndi",
+      "name": "T_incremented",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_phi": {
+      "__class__": "LogTocElement",
+      "ident": 301,
+      "group": "posCtrlIndi",
+      "name": "cmd_phi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_theta": {
+      "__class__": "LogTocElement",
+      "ident": 302,
+      "group": "posCtrlIndi",
+      "name": "cmd_theta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "posCtl": {
+    "targetVX": {
+      "__class__": "LogTocElement",
+      "ident": 303,
+      "group": "posCtl",
+      "name": "targetVX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetVY": {
+      "__class__": "LogTocElement",
+      "ident": 304,
+      "group": "posCtl",
+      "name": "targetVY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetVZ": {
+      "__class__": "LogTocElement",
+      "ident": 305,
+      "group": "posCtl",
+      "name": "targetVZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetX": {
+      "__class__": "LogTocElement",
+      "ident": 306,
+      "group": "posCtl",
+      "name": "targetX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetY": {
+      "__class__": "LogTocElement",
+      "ident": 307,
+      "group": "posCtl",
+      "name": "targetY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetZ": {
+      "__class__": "LogTocElement",
+      "ident": 308,
+      "group": "posCtl",
+      "name": "targetZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyVX": {
+      "__class__": "LogTocElement",
+      "ident": 309,
+      "group": "posCtl",
+      "name": "bodyVX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyVY": {
+      "__class__": "LogTocElement",
+      "ident": 310,
+      "group": "posCtl",
+      "name": "bodyVY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyX": {
+      "__class__": "LogTocElement",
+      "ident": 311,
+      "group": "posCtl",
+      "name": "bodyX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bodyY": {
+      "__class__": "LogTocElement",
+      "ident": 312,
+      "group": "posCtl",
+      "name": "bodyY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xp": {
+      "__class__": "LogTocElement",
+      "ident": 313,
+      "group": "posCtl",
+      "name": "Xp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xi": {
+      "__class__": "LogTocElement",
+      "ident": 314,
+      "group": "posCtl",
+      "name": "Xi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xd": {
+      "__class__": "LogTocElement",
+      "ident": 315,
+      "group": "posCtl",
+      "name": "Xd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xff": {
+      "__class__": "LogTocElement",
+      "ident": 316,
+      "group": "posCtl",
+      "name": "Xff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yp": {
+      "__class__": "LogTocElement",
+      "ident": 317,
+      "group": "posCtl",
+      "name": "Yp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yi": {
+      "__class__": "LogTocElement",
+      "ident": 318,
+      "group": "posCtl",
+      "name": "Yi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yd": {
+      "__class__": "LogTocElement",
+      "ident": 319,
+      "group": "posCtl",
+      "name": "Yd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yff": {
+      "__class__": "LogTocElement",
+      "ident": 320,
+      "group": "posCtl",
+      "name": "Yff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zp": {
+      "__class__": "LogTocElement",
+      "ident": 321,
+      "group": "posCtl",
+      "name": "Zp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zi": {
+      "__class__": "LogTocElement",
+      "ident": 322,
+      "group": "posCtl",
+      "name": "Zi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zd": {
+      "__class__": "LogTocElement",
+      "ident": 323,
+      "group": "posCtl",
+      "name": "Zd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zff": {
+      "__class__": "LogTocElement",
+      "ident": 324,
+      "group": "posCtl",
+      "name": "Zff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXp": {
+      "__class__": "LogTocElement",
+      "ident": 325,
+      "group": "posCtl",
+      "name": "VXp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXi": {
+      "__class__": "LogTocElement",
+      "ident": 326,
+      "group": "posCtl",
+      "name": "VXi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXd": {
+      "__class__": "LogTocElement",
+      "ident": 327,
+      "group": "posCtl",
+      "name": "VXd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXff": {
+      "__class__": "LogTocElement",
+      "ident": 328,
+      "group": "posCtl",
+      "name": "VXff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYp": {
+      "__class__": "LogTocElement",
+      "ident": 329,
+      "group": "posCtl",
+      "name": "VYp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYi": {
+      "__class__": "LogTocElement",
+      "ident": 330,
+      "group": "posCtl",
+      "name": "VYi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYd": {
+      "__class__": "LogTocElement",
+      "ident": 331,
+      "group": "posCtl",
+      "name": "VYd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VYff": {
+      "__class__": "LogTocElement",
+      "ident": 332,
+      "group": "posCtl",
+      "name": "VYff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZp": {
+      "__class__": "LogTocElement",
+      "ident": 333,
+      "group": "posCtl",
+      "name": "VZp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZi": {
+      "__class__": "LogTocElement",
+      "ident": 334,
+      "group": "posCtl",
+      "name": "VZi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZd": {
+      "__class__": "LogTocElement",
+      "ident": 335,
+      "group": "posCtl",
+      "name": "VZd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZff": {
+      "__class__": "LogTocElement",
+      "ident": 336,
+      "group": "posCtl",
+      "name": "VZff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "posEstAlt": {
+    "estimatedZ": {
+      "__class__": "LogTocElement",
+      "ident": 337,
+      "group": "posEstAlt",
+      "name": "estimatedZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estVZ": {
+      "__class__": "LogTocElement",
+      "ident": 338,
+      "group": "posEstAlt",
+      "name": "estVZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velocityZ": {
+      "__class__": "LogTocElement",
+      "ident": 339,
+      "group": "posEstAlt",
+      "name": "velocityZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "range": {
+    "front": {
+      "__class__": "LogTocElement",
+      "ident": 340,
+      "group": "range",
+      "name": "front",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "back": {
+      "__class__": "LogTocElement",
+      "ident": 341,
+      "group": "range",
+      "name": "back",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "up": {
+      "__class__": "LogTocElement",
+      "ident": 342,
+      "group": "range",
+      "name": "up",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "left": {
+      "__class__": "LogTocElement",
+      "ident": 343,
+      "group": "range",
+      "name": "left",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "right": {
+      "__class__": "LogTocElement",
+      "ident": 344,
+      "group": "range",
+      "name": "right",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "zrange": {
+      "__class__": "LogTocElement",
+      "ident": 345,
+      "group": "range",
+      "name": "zrange",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "sensfusion6": {
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 346,
+      "group": "sensfusion6",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 347,
+      "group": "sensfusion6",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 348,
+      "group": "sensfusion6",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 349,
+      "group": "sensfusion6",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityX": {
+      "__class__": "LogTocElement",
+      "ident": 350,
+      "group": "sensfusion6",
+      "name": "gravityX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityY": {
+      "__class__": "LogTocElement",
+      "ident": 351,
+      "group": "sensfusion6",
+      "name": "gravityY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityZ": {
+      "__class__": "LogTocElement",
+      "ident": 352,
+      "group": "sensfusion6",
+      "name": "gravityZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accZbase": {
+      "__class__": "LogTocElement",
+      "ident": 353,
+      "group": "sensfusion6",
+      "name": "accZbase",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "isInit": {
+      "__class__": "LogTocElement",
+      "ident": 354,
+      "group": "sensfusion6",
+      "name": "isInit",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isCalibrated": {
+      "__class__": "LogTocElement",
+      "ident": 355,
+      "group": "sensfusion6",
+      "name": "isCalibrated",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "acc": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 356,
+      "group": "acc",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 357,
+      "group": "acc",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 358,
+      "group": "acc",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "baro": {
+    "asl": {
+      "__class__": "LogTocElement",
+      "ident": 359,
+      "group": "baro",
+      "name": "asl",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "temp": {
+      "__class__": "LogTocElement",
+      "ident": 360,
+      "group": "baro",
+      "name": "temp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure": {
+      "__class__": "LogTocElement",
+      "ident": 361,
+      "group": "baro",
+      "name": "pressure",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrltarget": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 362,
+      "group": "ctrltarget",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 363,
+      "group": "ctrltarget",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 364,
+      "group": "ctrltarget",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 365,
+      "group": "ctrltarget",
+      "name": "vx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 366,
+      "group": "ctrltarget",
+      "name": "vy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 367,
+      "group": "ctrltarget",
+      "name": "vz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 368,
+      "group": "ctrltarget",
+      "name": "ax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 369,
+      "group": "ctrltarget",
+      "name": "ay",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 370,
+      "group": "ctrltarget",
+      "name": "az",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 371,
+      "group": "ctrltarget",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 372,
+      "group": "ctrltarget",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 373,
+      "group": "ctrltarget",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrltargetZ": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 374,
+      "group": "ctrltargetZ",
+      "name": "x",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 375,
+      "group": "ctrltargetZ",
+      "name": "y",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 376,
+      "group": "ctrltargetZ",
+      "name": "z",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 377,
+      "group": "ctrltargetZ",
+      "name": "vx",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 378,
+      "group": "ctrltargetZ",
+      "name": "vy",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 379,
+      "group": "ctrltargetZ",
+      "name": "vz",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 380,
+      "group": "ctrltargetZ",
+      "name": "ax",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 381,
+      "group": "ctrltargetZ",
+      "name": "ay",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 382,
+      "group": "ctrltargetZ",
+      "name": "az",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "mag": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 383,
+      "group": "mag",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 384,
+      "group": "mag",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 385,
+      "group": "mag",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "stabilizer": {
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 386,
+      "group": "stabilizer",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 387,
+      "group": "stabilizer",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 388,
+      "group": "stabilizer",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "thrust": {
+      "__class__": "LogTocElement",
+      "ident": 389,
+      "group": "stabilizer",
+      "name": "thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtStab": {
+      "__class__": "LogTocElement",
+      "ident": 390,
+      "group": "stabilizer",
+      "name": "rtStab",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "intToOut": {
+      "__class__": "LogTocElement",
+      "ident": 391,
+      "group": "stabilizer",
+      "name": "intToOut",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "stateEstimate": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 392,
+      "group": "stateEstimate",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 393,
+      "group": "stateEstimate",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 394,
+      "group": "stateEstimate",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 395,
+      "group": "stateEstimate",
+      "name": "vx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 396,
+      "group": "stateEstimate",
+      "name": "vy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 397,
+      "group": "stateEstimate",
+      "name": "vz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 398,
+      "group": "stateEstimate",
+      "name": "ax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 399,
+      "group": "stateEstimate",
+      "name": "ay",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 400,
+      "group": "stateEstimate",
+      "name": "az",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 401,
+      "group": "stateEstimate",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 402,
+      "group": "stateEstimate",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 403,
+      "group": "stateEstimate",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 404,
+      "group": "stateEstimate",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 405,
+      "group": "stateEstimate",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 406,
+      "group": "stateEstimate",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 407,
+      "group": "stateEstimate",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "stateEstimateZ": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 408,
+      "group": "stateEstimateZ",
+      "name": "x",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 409,
+      "group": "stateEstimateZ",
+      "name": "y",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 410,
+      "group": "stateEstimateZ",
+      "name": "z",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 411,
+      "group": "stateEstimateZ",
+      "name": "vx",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 412,
+      "group": "stateEstimateZ",
+      "name": "vy",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 413,
+      "group": "stateEstimateZ",
+      "name": "vz",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 414,
+      "group": "stateEstimateZ",
+      "name": "ax",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 415,
+      "group": "stateEstimateZ",
+      "name": "ay",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 416,
+      "group": "stateEstimateZ",
+      "name": "az",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "quat": {
+      "__class__": "LogTocElement",
+      "ident": 417,
+      "group": "stateEstimateZ",
+      "name": "quat",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "rateRoll": {
+      "__class__": "LogTocElement",
+      "ident": 418,
+      "group": "stateEstimateZ",
+      "name": "rateRoll",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ratePitch": {
+      "__class__": "LogTocElement",
+      "ident": 419,
+      "group": "stateEstimateZ",
+      "name": "ratePitch",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "rateYaw": {
+      "__class__": "LogTocElement",
+      "ident": 420,
+      "group": "stateEstimateZ",
+      "name": "rateYaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "sys": {
+    "canfly": {
+      "__class__": "LogTocElement",
+      "ident": 421,
+      "group": "sys",
+      "name": "canfly",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isFlying": {
+      "__class__": "LogTocElement",
+      "ident": 422,
+      "group": "sys",
+      "name": "isFlying",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isTumbled": {
+      "__class__": "LogTocElement",
+      "ident": 423,
+      "group": "sys",
+      "name": "isTumbled",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "armed": {
+      "__class__": "LogTocElement",
+      "ident": 424,
+      "group": "sys",
+      "name": "armed",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0
+    }
+  },
+  "tdoaEngine": {
+    "stRx": {
+      "__class__": "LogTocElement",
+      "ident": 425,
+      "group": "tdoaEngine",
+      "name": "stRx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stEst": {
+      "__class__": "LogTocElement",
+      "ident": 426,
+      "group": "tdoaEngine",
+      "name": "stEst",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stTime": {
+      "__class__": "LogTocElement",
+      "ident": 427,
+      "group": "tdoaEngine",
+      "name": "stTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stFound": {
+      "__class__": "LogTocElement",
+      "ident": 428,
+      "group": "tdoaEngine",
+      "name": "stFound",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stCc": {
+      "__class__": "LogTocElement",
+      "ident": 429,
+      "group": "tdoaEngine",
+      "name": "stCc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stHit": {
+      "__class__": "LogTocElement",
+      "ident": 430,
+      "group": "tdoaEngine",
+      "name": "stHit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stMiss": {
+      "__class__": "LogTocElement",
+      "ident": 431,
+      "group": "tdoaEngine",
+      "name": "stMiss",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc": {
+      "__class__": "LogTocElement",
+      "ident": 432,
+      "group": "tdoaEngine",
+      "name": "cc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "tof": {
+      "__class__": "LogTocElement",
+      "ident": 433,
+      "group": "tdoaEngine",
+      "name": "tof",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "tdoa": {
+      "__class__": "LogTocElement",
+      "ident": 434,
+      "group": "tdoaEngine",
+      "name": "tdoa",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "DTR_P2P": {
+    "rx_state": {
+      "__class__": "LogTocElement",
+      "ident": 435,
+      "group": "DTR_P2P",
+      "name": "rx_state",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "tx_state": {
+      "__class__": "LogTocElement",
+      "ident": 436,
+      "group": "DTR_P2P",
+      "name": "tx_state",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "kalman_pred": {
+    "predNX": {
+      "__class__": "LogTocElement",
+      "ident": 437,
+      "group": "kalman_pred",
+      "name": "predNX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "predNY": {
+      "__class__": "LogTocElement",
+      "ident": 438,
+      "group": "kalman_pred",
+      "name": "predNY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "measNX": {
+      "__class__": "LogTocElement",
+      "ident": 439,
+      "group": "kalman_pred",
+      "name": "measNX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "measNY": {
+      "__class__": "LogTocElement",
+      "ident": 440,
+      "group": "kalman_pred",
+      "name": "measNY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "lighthouse": {
+    "validAngles": {
+      "__class__": "LogTocElement",
+      "ident": 441,
+      "group": "lighthouse",
+      "name": "validAngles",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rawAngle0x": {
+      "__class__": "LogTocElement",
+      "ident": 442,
+      "group": "lighthouse",
+      "name": "rawAngle0x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0y": {
+      "__class__": "LogTocElement",
+      "ident": 443,
+      "group": "lighthouse",
+      "name": "rawAngle0y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1x": {
+      "__class__": "LogTocElement",
+      "ident": 444,
+      "group": "lighthouse",
+      "name": "rawAngle1x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1y": {
+      "__class__": "LogTocElement",
+      "ident": 445,
+      "group": "lighthouse",
+      "name": "rawAngle1y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x": {
+      "__class__": "LogTocElement",
+      "ident": 446,
+      "group": "lighthouse",
+      "name": "angle0x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y": {
+      "__class__": "LogTocElement",
+      "ident": 447,
+      "group": "lighthouse",
+      "name": "angle0y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x": {
+      "__class__": "LogTocElement",
+      "ident": 448,
+      "group": "lighthouse",
+      "name": "angle1x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y": {
+      "__class__": "LogTocElement",
+      "ident": 449,
+      "group": "lighthouse",
+      "name": "angle1y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_1": {
+      "__class__": "LogTocElement",
+      "ident": 450,
+      "group": "lighthouse",
+      "name": "angle0x_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_1": {
+      "__class__": "LogTocElement",
+      "ident": 451,
+      "group": "lighthouse",
+      "name": "angle0y_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_1": {
+      "__class__": "LogTocElement",
+      "ident": 452,
+      "group": "lighthouse",
+      "name": "angle1x_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_1": {
+      "__class__": "LogTocElement",
+      "ident": 453,
+      "group": "lighthouse",
+      "name": "angle1y_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_2": {
+      "__class__": "LogTocElement",
+      "ident": 454,
+      "group": "lighthouse",
+      "name": "angle0x_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_2": {
+      "__class__": "LogTocElement",
+      "ident": 455,
+      "group": "lighthouse",
+      "name": "angle0y_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_2": {
+      "__class__": "LogTocElement",
+      "ident": 456,
+      "group": "lighthouse",
+      "name": "angle1x_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_2": {
+      "__class__": "LogTocElement",
+      "ident": 457,
+      "group": "lighthouse",
+      "name": "angle1y_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_3": {
+      "__class__": "LogTocElement",
+      "ident": 458,
+      "group": "lighthouse",
+      "name": "angle0x_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_3": {
+      "__class__": "LogTocElement",
+      "ident": 459,
+      "group": "lighthouse",
+      "name": "angle0y_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_3": {
+      "__class__": "LogTocElement",
+      "ident": 460,
+      "group": "lighthouse",
+      "name": "angle1x_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_3": {
+      "__class__": "LogTocElement",
+      "ident": 461,
+      "group": "lighthouse",
+      "name": "angle1y_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0xlh2": {
+      "__class__": "LogTocElement",
+      "ident": 462,
+      "group": "lighthouse",
+      "name": "rawAngle0xlh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0ylh2": {
+      "__class__": "LogTocElement",
+      "ident": 463,
+      "group": "lighthouse",
+      "name": "rawAngle0ylh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1xlh2": {
+      "__class__": "LogTocElement",
+      "ident": 464,
+      "group": "lighthouse",
+      "name": "rawAngle1xlh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1ylh2": {
+      "__class__": "LogTocElement",
+      "ident": 465,
+      "group": "lighthouse",
+      "name": "rawAngle1ylh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 466,
+      "group": "lighthouse",
+      "name": "angle0x_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 467,
+      "group": "lighthouse",
+      "name": "angle0y_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 468,
+      "group": "lighthouse",
+      "name": "angle1x_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 469,
+      "group": "lighthouse",
+      "name": "angle1y_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "width0": {
+      "__class__": "LogTocElement",
+      "ident": 470,
+      "group": "lighthouse",
+      "name": "width0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width1": {
+      "__class__": "LogTocElement",
+      "ident": 471,
+      "group": "lighthouse",
+      "name": "width1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width2": {
+      "__class__": "LogTocElement",
+      "ident": 472,
+      "group": "lighthouse",
+      "name": "width2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width3": {
+      "__class__": "LogTocElement",
+      "ident": 473,
+      "group": "lighthouse",
+      "name": "width3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "comSync": {
+      "__class__": "LogTocElement",
+      "ident": 474,
+      "group": "lighthouse",
+      "name": "comSync",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "bsAvailable": {
+      "__class__": "LogTocElement",
+      "ident": 475,
+      "group": "lighthouse",
+      "name": "bsAvailable",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsReceive": {
+      "__class__": "LogTocElement",
+      "ident": 476,
+      "group": "lighthouse",
+      "name": "bsReceive",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsActive": {
+      "__class__": "LogTocElement",
+      "ident": 477,
+      "group": "lighthouse",
+      "name": "bsActive",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalUd": {
+      "__class__": "LogTocElement",
+      "ident": 478,
+      "group": "lighthouse",
+      "name": "bsCalUd",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalCon": {
+      "__class__": "LogTocElement",
+      "ident": 479,
+      "group": "lighthouse",
+      "name": "bsCalCon",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "status": {
+      "__class__": "LogTocElement",
+      "ident": 480,
+      "group": "lighthouse",
+      "name": "status",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "posRt": {
+      "__class__": "LogTocElement",
+      "ident": 481,
+      "group": "lighthouse",
+      "name": "posRt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estBs0Rt": {
+      "__class__": "LogTocElement",
+      "ident": 482,
+      "group": "lighthouse",
+      "name": "estBs0Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estBs1Rt": {
+      "__class__": "LogTocElement",
+      "ident": 483,
+      "group": "lighthouse",
+      "name": "estBs1Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 484,
+      "group": "lighthouse",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 485,
+      "group": "lighthouse",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 486,
+      "group": "lighthouse",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "delta": {
+      "__class__": "LogTocElement",
+      "ident": 487,
+      "group": "lighthouse",
+      "name": "delta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bsGeoVal": {
+      "__class__": "LogTocElement",
+      "ident": 488,
+      "group": "lighthouse",
+      "name": "bsGeoVal",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalVal": {
+      "__class__": "LogTocElement",
+      "ident": 489,
+      "group": "lighthouse",
+      "name": "bsCalVal",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "disProb": {
+      "__class__": "LogTocElement",
+      "ident": 490,
+      "group": "lighthouse",
+      "name": "disProb",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  }
+}
\ No newline at end of file
diff --git a/crazyflie_demos/cache/59A4CB7D.json b/crazyflie_demos/cache/59A4CB7D.json
new file mode 100644
index 0000000000000000000000000000000000000000..93984ab9376916170975bb1107b4c648bc9145f4
--- /dev/null
+++ b/crazyflie_demos/cache/59A4CB7D.json
@@ -0,0 +1,2840 @@
+{
+  "activeMarker": {
+    "front": {
+      "__class__": "ParamTocElement",
+      "ident": 0,
+      "group": "activeMarker",
+      "name": "front",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "back": {
+      "__class__": "ParamTocElement",
+      "ident": 1,
+      "group": "activeMarker",
+      "name": "back",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "left": {
+      "__class__": "ParamTocElement",
+      "ident": 2,
+      "group": "activeMarker",
+      "name": "left",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "right": {
+      "__class__": "ParamTocElement",
+      "ident": 3,
+      "group": "activeMarker",
+      "name": "right",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "mode": {
+      "__class__": "ParamTocElement",
+      "ident": 4,
+      "group": "activeMarker",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "poll": {
+      "__class__": "ParamTocElement",
+      "ident": 5,
+      "group": "activeMarker",
+      "name": "poll",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "deck": {
+    "bcActiveMarker": {
+      "__class__": "ParamTocElement",
+      "ident": 6,
+      "group": "deck",
+      "name": "bcActiveMarker",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcAI": {
+      "__class__": "ParamTocElement",
+      "ident": 7,
+      "group": "deck",
+      "name": "bcAI",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcBuzzer": {
+      "__class__": "ParamTocElement",
+      "ident": 8,
+      "group": "deck",
+      "name": "bcBuzzer",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcFlow": {
+      "__class__": "ParamTocElement",
+      "ident": 9,
+      "group": "deck",
+      "name": "bcFlow",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcFlow2": {
+      "__class__": "ParamTocElement",
+      "ident": 10,
+      "group": "deck",
+      "name": "bcFlow2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcLedRing": {
+      "__class__": "ParamTocElement",
+      "ident": 11,
+      "group": "deck",
+      "name": "bcLedRing",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcLighthouse4": {
+      "__class__": "ParamTocElement",
+      "ident": 12,
+      "group": "deck",
+      "name": "bcLighthouse4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcDWM1000": {
+      "__class__": "ParamTocElement",
+      "ident": 13,
+      "group": "deck",
+      "name": "bcDWM1000",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcLoco": {
+      "__class__": "ParamTocElement",
+      "ident": 14,
+      "group": "deck",
+      "name": "bcLoco",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcMultiranger": {
+      "__class__": "ParamTocElement",
+      "ident": 15,
+      "group": "deck",
+      "name": "bcMultiranger",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcOA": {
+      "__class__": "ParamTocElement",
+      "ident": 16,
+      "group": "deck",
+      "name": "bcOA",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcUSD": {
+      "__class__": "ParamTocElement",
+      "ident": 17,
+      "group": "deck",
+      "name": "bcUSD",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcZRanger": {
+      "__class__": "ParamTocElement",
+      "ident": 18,
+      "group": "deck",
+      "name": "bcZRanger",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcZRanger2": {
+      "__class__": "ParamTocElement",
+      "ident": 19,
+      "group": "deck",
+      "name": "bcZRanger2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "motion": {
+    "disable": {
+      "__class__": "ParamTocElement",
+      "ident": 20,
+      "group": "motion",
+      "name": "disable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "adaptive": {
+      "__class__": "ParamTocElement",
+      "ident": 21,
+      "group": "motion",
+      "name": "adaptive",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "flowStdFixed": {
+      "__class__": "ParamTocElement",
+      "ident": 22,
+      "group": "motion",
+      "name": "flowStdFixed",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ring": {
+    "effect": {
+      "__class__": "ParamTocElement",
+      "ident": 23,
+      "group": "ring",
+      "name": "effect",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "neffect": {
+      "__class__": "ParamTocElement",
+      "ident": 24,
+      "group": "ring",
+      "name": "neffect",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "solidRed": {
+      "__class__": "ParamTocElement",
+      "ident": 25,
+      "group": "ring",
+      "name": "solidRed",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "solidGreen": {
+      "__class__": "ParamTocElement",
+      "ident": 26,
+      "group": "ring",
+      "name": "solidGreen",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "solidBlue": {
+      "__class__": "ParamTocElement",
+      "ident": 27,
+      "group": "ring",
+      "name": "solidBlue",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "headlightEnable": {
+      "__class__": "ParamTocElement",
+      "ident": 28,
+      "group": "ring",
+      "name": "headlightEnable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "emptyCharge": {
+      "__class__": "ParamTocElement",
+      "ident": 29,
+      "group": "ring",
+      "name": "emptyCharge",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "fullCharge": {
+      "__class__": "ParamTocElement",
+      "ident": 30,
+      "group": "ring",
+      "name": "fullCharge",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "fadeColor": {
+      "__class__": "ParamTocElement",
+      "ident": 31,
+      "group": "ring",
+      "name": "fadeColor",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0,
+      "extended": false
+    },
+    "fadeTime": {
+      "__class__": "ParamTocElement",
+      "ident": 32,
+      "group": "ring",
+      "name": "fadeTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "system": {
+    "highlight": {
+      "__class__": "ParamTocElement",
+      "ident": 33,
+      "group": "system",
+      "name": "highlight",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "storageStats": {
+      "__class__": "ParamTocElement",
+      "ident": 34,
+      "group": "system",
+      "name": "storageStats",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "storageReformat": {
+      "__class__": "ParamTocElement",
+      "ident": 35,
+      "group": "system",
+      "name": "storageReformat",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "taskDump": {
+      "__class__": "ParamTocElement",
+      "ident": 36,
+      "group": "system",
+      "name": "taskDump",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "selftestPassed": {
+      "__class__": "ParamTocElement",
+      "ident": 37,
+      "group": "system",
+      "name": "selftestPassed",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 1,
+      "extended": false
+    },
+    "forceArm": {
+      "__class__": "ParamTocElement",
+      "ident": 38,
+      "group": "system",
+      "name": "forceArm",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0,
+      "extended": true
+    },
+    "assertInfo": {
+      "__class__": "ParamTocElement",
+      "ident": 39,
+      "group": "system",
+      "name": "assertInfo",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "loco": {
+    "mode": {
+      "__class__": "ParamTocElement",
+      "ident": 40,
+      "group": "loco",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "tdoa2": {
+    "stddev": {
+      "__class__": "ParamTocElement",
+      "ident": 41,
+      "group": "tdoa2",
+      "name": "stddev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "tdoa3": {
+    "stddev": {
+      "__class__": "ParamTocElement",
+      "ident": 42,
+      "group": "tdoa3",
+      "name": "stddev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "multiranger": {
+    "filterMask": {
+      "__class__": "ParamTocElement",
+      "ident": 43,
+      "group": "multiranger",
+      "name": "filterMask",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "usd": {
+    "canLog": {
+      "__class__": "ParamTocElement",
+      "ident": 44,
+      "group": "usd",
+      "name": "canLog",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "logging": {
+      "__class__": "ParamTocElement",
+      "ident": 45,
+      "group": "usd",
+      "name": "logging",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "led": {
+    "bitmask": {
+      "__class__": "ParamTocElement",
+      "ident": 46,
+      "group": "led",
+      "name": "bitmask",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "motorPowerSet": {
+    "enable": {
+      "__class__": "ParamTocElement",
+      "ident": 47,
+      "group": "motorPowerSet",
+      "name": "enable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "m1": {
+      "__class__": "ParamTocElement",
+      "ident": 48,
+      "group": "motorPowerSet",
+      "name": "m1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m2": {
+      "__class__": "ParamTocElement",
+      "ident": 49,
+      "group": "motorPowerSet",
+      "name": "m2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m3": {
+      "__class__": "ParamTocElement",
+      "ident": 50,
+      "group": "motorPowerSet",
+      "name": "m3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m4": {
+      "__class__": "ParamTocElement",
+      "ident": 51,
+      "group": "motorPowerSet",
+      "name": "m4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "pm": {
+    "lowVoltage": {
+      "__class__": "ParamTocElement",
+      "ident": 52,
+      "group": "pm",
+      "name": "lowVoltage",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "criticalLowVoltage": {
+      "__class__": "ParamTocElement",
+      "ident": 53,
+      "group": "pm",
+      "name": "criticalLowVoltage",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "imu_sensors": {
+    "BMP388": {
+      "__class__": "ParamTocElement",
+      "ident": 54,
+      "group": "imu_sensors",
+      "name": "BMP388",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "imuPhi": {
+      "__class__": "ParamTocElement",
+      "ident": 55,
+      "group": "imu_sensors",
+      "name": "imuPhi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuTheta": {
+      "__class__": "ParamTocElement",
+      "ident": 56,
+      "group": "imu_sensors",
+      "name": "imuTheta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuPsi": {
+      "__class__": "ParamTocElement",
+      "ident": 57,
+      "group": "imu_sensors",
+      "name": "imuPsi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "AK8963": {
+      "__class__": "ParamTocElement",
+      "ident": 58,
+      "group": "imu_sensors",
+      "name": "AK8963",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "LPS25H": {
+      "__class__": "ParamTocElement",
+      "ident": 59,
+      "group": "imu_sensors",
+      "name": "LPS25H",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "imu_tests": {
+    "MPU6500": {
+      "__class__": "ParamTocElement",
+      "ident": 60,
+      "group": "imu_tests",
+      "name": "MPU6500",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "AK8963": {
+      "__class__": "ParamTocElement",
+      "ident": 61,
+      "group": "imu_tests",
+      "name": "AK8963",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "LPS25H": {
+      "__class__": "ParamTocElement",
+      "ident": 62,
+      "group": "imu_tests",
+      "name": "LPS25H",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "imuPhi": {
+      "__class__": "ParamTocElement",
+      "ident": 63,
+      "group": "imu_tests",
+      "name": "imuPhi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuTheta": {
+      "__class__": "ParamTocElement",
+      "ident": 64,
+      "group": "imu_tests",
+      "name": "imuTheta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuPsi": {
+      "__class__": "ParamTocElement",
+      "ident": 65,
+      "group": "imu_tests",
+      "name": "imuPsi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "syslink": {
+    "probe": {
+      "__class__": "ParamTocElement",
+      "ident": 66,
+      "group": "syslink",
+      "name": "probe",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "pid_attitude": {
+    "roll_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 67,
+      "group": "pid_attitude",
+      "name": "roll_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 68,
+      "group": "pid_attitude",
+      "name": "roll_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 69,
+      "group": "pid_attitude",
+      "name": "roll_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 70,
+      "group": "pid_attitude",
+      "name": "roll_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 71,
+      "group": "pid_attitude",
+      "name": "pitch_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 72,
+      "group": "pid_attitude",
+      "name": "pitch_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 73,
+      "group": "pid_attitude",
+      "name": "pitch_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 74,
+      "group": "pid_attitude",
+      "name": "pitch_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 75,
+      "group": "pid_attitude",
+      "name": "yaw_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 76,
+      "group": "pid_attitude",
+      "name": "yaw_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 77,
+      "group": "pid_attitude",
+      "name": "yaw_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 78,
+      "group": "pid_attitude",
+      "name": "yaw_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yawMaxDelta": {
+      "__class__": "ParamTocElement",
+      "ident": 79,
+      "group": "pid_attitude",
+      "name": "yawMaxDelta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "attFiltEn": {
+      "__class__": "ParamTocElement",
+      "ident": 80,
+      "group": "pid_attitude",
+      "name": "attFiltEn",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0,
+      "extended": true
+    },
+    "attFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 81,
+      "group": "pid_attitude",
+      "name": "attFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "pid_rate": {
+    "roll_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 82,
+      "group": "pid_rate",
+      "name": "roll_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 83,
+      "group": "pid_rate",
+      "name": "roll_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 84,
+      "group": "pid_rate",
+      "name": "roll_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 85,
+      "group": "pid_rate",
+      "name": "roll_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 86,
+      "group": "pid_rate",
+      "name": "pitch_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 87,
+      "group": "pid_rate",
+      "name": "pitch_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 88,
+      "group": "pid_rate",
+      "name": "pitch_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 89,
+      "group": "pid_rate",
+      "name": "pitch_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 90,
+      "group": "pid_rate",
+      "name": "yaw_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 91,
+      "group": "pid_rate",
+      "name": "yaw_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 92,
+      "group": "pid_rate",
+      "name": "yaw_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 93,
+      "group": "pid_rate",
+      "name": "yaw_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "rateFiltEn": {
+      "__class__": "ParamTocElement",
+      "ident": 94,
+      "group": "pid_rate",
+      "name": "rateFiltEn",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0,
+      "extended": true
+    },
+    "omxFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 95,
+      "group": "pid_rate",
+      "name": "omxFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "omyFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 96,
+      "group": "pid_rate",
+      "name": "omyFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "omzFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 97,
+      "group": "pid_rate",
+      "name": "omzFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "colAv": {
+    "enable": {
+      "__class__": "ParamTocElement",
+      "ident": 98,
+      "group": "colAv",
+      "name": "enable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidX": {
+      "__class__": "ParamTocElement",
+      "ident": 99,
+      "group": "colAv",
+      "name": "ellipsoidX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidY": {
+      "__class__": "ParamTocElement",
+      "ident": 100,
+      "group": "colAv",
+      "name": "ellipsoidY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidZ": {
+      "__class__": "ParamTocElement",
+      "ident": 101,
+      "group": "colAv",
+      "name": "ellipsoidZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinX": {
+      "__class__": "ParamTocElement",
+      "ident": 102,
+      "group": "colAv",
+      "name": "bboxMinX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinY": {
+      "__class__": "ParamTocElement",
+      "ident": 103,
+      "group": "colAv",
+      "name": "bboxMinY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinZ": {
+      "__class__": "ParamTocElement",
+      "ident": 104,
+      "group": "colAv",
+      "name": "bboxMinZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxX": {
+      "__class__": "ParamTocElement",
+      "ident": 105,
+      "group": "colAv",
+      "name": "bboxMaxX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxY": {
+      "__class__": "ParamTocElement",
+      "ident": 106,
+      "group": "colAv",
+      "name": "bboxMaxY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxZ": {
+      "__class__": "ParamTocElement",
+      "ident": 107,
+      "group": "colAv",
+      "name": "bboxMaxZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "horizon": {
+      "__class__": "ParamTocElement",
+      "ident": 108,
+      "group": "colAv",
+      "name": "horizon",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxSpeed": {
+      "__class__": "ParamTocElement",
+      "ident": 109,
+      "group": "colAv",
+      "name": "maxSpeed",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "sidestepThrsh": {
+      "__class__": "ParamTocElement",
+      "ident": 110,
+      "group": "colAv",
+      "name": "sidestepThrsh",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxPeerLocAge": {
+      "__class__": "ParamTocElement",
+      "ident": 111,
+      "group": "colAv",
+      "name": "maxPeerLocAge",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0,
+      "extended": false
+    },
+    "vorTol": {
+      "__class__": "ParamTocElement",
+      "ident": 112,
+      "group": "colAv",
+      "name": "vorTol",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vorIters": {
+      "__class__": "ParamTocElement",
+      "ident": 113,
+      "group": "colAv",
+      "name": "vorIters",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "commander": {
+    "enHighLevel": {
+      "__class__": "ParamTocElement",
+      "ident": 114,
+      "group": "commander",
+      "name": "enHighLevel",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ctrlINDI": {
+    "thrust_threshold": {
+      "__class__": "ParamTocElement",
+      "ident": 115,
+      "group": "ctrlINDI",
+      "name": "thrust_threshold",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bound_ctrl_input": {
+      "__class__": "ParamTocElement",
+      "ident": 116,
+      "group": "ctrlINDI",
+      "name": "bound_ctrl_input",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_p": {
+      "__class__": "ParamTocElement",
+      "ident": 117,
+      "group": "ctrlINDI",
+      "name": "g1_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_q": {
+      "__class__": "ParamTocElement",
+      "ident": 118,
+      "group": "ctrlINDI",
+      "name": "g1_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_r": {
+      "__class__": "ParamTocElement",
+      "ident": 119,
+      "group": "ctrlINDI",
+      "name": "g1_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g2": {
+      "__class__": "ParamTocElement",
+      "ident": 120,
+      "group": "ctrlINDI",
+      "name": "g2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_p": {
+      "__class__": "ParamTocElement",
+      "ident": 121,
+      "group": "ctrlINDI",
+      "name": "ref_err_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_q": {
+      "__class__": "ParamTocElement",
+      "ident": 122,
+      "group": "ctrlINDI",
+      "name": "ref_err_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_r": {
+      "__class__": "ParamTocElement",
+      "ident": 123,
+      "group": "ctrlINDI",
+      "name": "ref_err_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_p": {
+      "__class__": "ParamTocElement",
+      "ident": 124,
+      "group": "ctrlINDI",
+      "name": "ref_rate_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_q": {
+      "__class__": "ParamTocElement",
+      "ident": 125,
+      "group": "ctrlINDI",
+      "name": "ref_rate_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_r": {
+      "__class__": "ParamTocElement",
+      "ident": 126,
+      "group": "ctrlINDI",
+      "name": "ref_rate_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_p": {
+      "__class__": "ParamTocElement",
+      "ident": 127,
+      "group": "ctrlINDI",
+      "name": "act_dyn_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_q": {
+      "__class__": "ParamTocElement",
+      "ident": 128,
+      "group": "ctrlINDI",
+      "name": "act_dyn_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_r": {
+      "__class__": "ParamTocElement",
+      "ident": 129,
+      "group": "ctrlINDI",
+      "name": "act_dyn_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "filt_cutoff": {
+      "__class__": "ParamTocElement",
+      "ident": 130,
+      "group": "ctrlINDI",
+      "name": "filt_cutoff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "filt_cutoff_r": {
+      "__class__": "ParamTocElement",
+      "ident": 131,
+      "group": "ctrlINDI",
+      "name": "filt_cutoff_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "outerLoopActive": {
+      "__class__": "ParamTocElement",
+      "ident": 132,
+      "group": "ctrlINDI",
+      "name": "outerLoopActive",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ctrlMel": {
+    "kp_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 133,
+      "group": "ctrlMel",
+      "name": "kp_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kd_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 134,
+      "group": "ctrlMel",
+      "name": "kd_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 135,
+      "group": "ctrlMel",
+      "name": "ki_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 136,
+      "group": "ctrlMel",
+      "name": "i_range_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kp_z": {
+      "__class__": "ParamTocElement",
+      "ident": 137,
+      "group": "ctrlMel",
+      "name": "kp_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kd_z": {
+      "__class__": "ParamTocElement",
+      "ident": 138,
+      "group": "ctrlMel",
+      "name": "kd_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_z": {
+      "__class__": "ParamTocElement",
+      "ident": 139,
+      "group": "ctrlMel",
+      "name": "ki_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_z": {
+      "__class__": "ParamTocElement",
+      "ident": 140,
+      "group": "ctrlMel",
+      "name": "i_range_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mass": {
+      "__class__": "ParamTocElement",
+      "ident": 141,
+      "group": "ctrlMel",
+      "name": "mass",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "massThrust": {
+      "__class__": "ParamTocElement",
+      "ident": 142,
+      "group": "ctrlMel",
+      "name": "massThrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kR_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 143,
+      "group": "ctrlMel",
+      "name": "kR_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kR_z": {
+      "__class__": "ParamTocElement",
+      "ident": 144,
+      "group": "ctrlMel",
+      "name": "kR_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kw_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 145,
+      "group": "ctrlMel",
+      "name": "kw_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kw_z": {
+      "__class__": "ParamTocElement",
+      "ident": 146,
+      "group": "ctrlMel",
+      "name": "kw_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_m_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 147,
+      "group": "ctrlMel",
+      "name": "ki_m_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_m_z": {
+      "__class__": "ParamTocElement",
+      "ident": 148,
+      "group": "ctrlMel",
+      "name": "ki_m_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kd_omega_rp": {
+      "__class__": "ParamTocElement",
+      "ident": 149,
+      "group": "ctrlMel",
+      "name": "kd_omega_rp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_m_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 150,
+      "group": "ctrlMel",
+      "name": "i_range_m_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_m_z": {
+      "__class__": "ParamTocElement",
+      "ident": 151,
+      "group": "ctrlMel",
+      "name": "i_range_m_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "ctrlAtt": {
+    "tau_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 152,
+      "group": "ctrlAtt",
+      "name": "tau_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zeta_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 153,
+      "group": "ctrlAtt",
+      "name": "zeta_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "tau_z": {
+      "__class__": "ParamTocElement",
+      "ident": 154,
+      "group": "ctrlAtt",
+      "name": "tau_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zeta_z": {
+      "__class__": "ParamTocElement",
+      "ident": 155,
+      "group": "ctrlAtt",
+      "name": "zeta_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "tau_rp": {
+      "__class__": "ParamTocElement",
+      "ident": 156,
+      "group": "ctrlAtt",
+      "name": "tau_rp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "mixing_factor": {
+      "__class__": "ParamTocElement",
+      "ident": 157,
+      "group": "ctrlAtt",
+      "name": "mixing_factor",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "coll_fairness": {
+      "__class__": "ParamTocElement",
+      "ident": 158,
+      "group": "ctrlAtt",
+      "name": "coll_fairness",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "cppm": {
+    "rateRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 159,
+      "group": "cppm",
+      "name": "rateRoll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ratePitch": {
+      "__class__": "ParamTocElement",
+      "ident": 160,
+      "group": "cppm",
+      "name": "ratePitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "angPitch": {
+      "__class__": "ParamTocElement",
+      "ident": 161,
+      "group": "cppm",
+      "name": "angPitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "angRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 162,
+      "group": "cppm",
+      "name": "angRoll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "rateYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 163,
+      "group": "cppm",
+      "name": "rateYaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "hlCommander": {
+    "vtoff": {
+      "__class__": "ParamTocElement",
+      "ident": 164,
+      "group": "hlCommander",
+      "name": "vtoff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vland": {
+      "__class__": "ParamTocElement",
+      "ident": 165,
+      "group": "hlCommander",
+      "name": "vland",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "flightmode": {
+    "althold": {
+      "__class__": "ParamTocElement",
+      "ident": 166,
+      "group": "flightmode",
+      "name": "althold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "poshold": {
+      "__class__": "ParamTocElement",
+      "ident": 167,
+      "group": "flightmode",
+      "name": "poshold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "posSet": {
+      "__class__": "ParamTocElement",
+      "ident": 168,
+      "group": "flightmode",
+      "name": "posSet",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "yawMode": {
+      "__class__": "ParamTocElement",
+      "ident": 169,
+      "group": "flightmode",
+      "name": "yawMode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModeRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 170,
+      "group": "flightmode",
+      "name": "stabModeRoll",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModePitch": {
+      "__class__": "ParamTocElement",
+      "ident": 171,
+      "group": "flightmode",
+      "name": "stabModePitch",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModeYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 172,
+      "group": "flightmode",
+      "name": "stabModeYaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "locSrv": {
+    "enRangeStreamFP32": {
+      "__class__": "ParamTocElement",
+      "ident": 173,
+      "group": "locSrv",
+      "name": "enRangeStreamFP32",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "enLhAngleStream": {
+      "__class__": "ParamTocElement",
+      "ident": 174,
+      "group": "locSrv",
+      "name": "enLhAngleStream",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "extPosStdDev": {
+      "__class__": "ParamTocElement",
+      "ident": 175,
+      "group": "locSrv",
+      "name": "extPosStdDev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "extQuatStdDev": {
+      "__class__": "ParamTocElement",
+      "ident": 176,
+      "group": "locSrv",
+      "name": "extQuatStdDev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "crtpsrv": {
+    "echoDelay": {
+      "__class__": "ParamTocElement",
+      "ident": 177,
+      "group": "crtpsrv",
+      "name": "echoDelay",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "kalman": {
+    "resetEstimation": {
+      "__class__": "ParamTocElement",
+      "ident": 178,
+      "group": "kalman",
+      "name": "resetEstimation",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "robustTdoa": {
+      "__class__": "ParamTocElement",
+      "ident": 179,
+      "group": "kalman",
+      "name": "robustTdoa",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "robustTwr": {
+      "__class__": "ParamTocElement",
+      "ident": 180,
+      "group": "kalman",
+      "name": "robustTwr",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "pNAcc_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 181,
+      "group": "kalman",
+      "name": "pNAcc_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNAcc_z": {
+      "__class__": "ParamTocElement",
+      "ident": 182,
+      "group": "kalman",
+      "name": "pNAcc_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNVel": {
+      "__class__": "ParamTocElement",
+      "ident": 183,
+      "group": "kalman",
+      "name": "pNVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNPos": {
+      "__class__": "ParamTocElement",
+      "ident": 184,
+      "group": "kalman",
+      "name": "pNPos",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNAtt": {
+      "__class__": "ParamTocElement",
+      "ident": 185,
+      "group": "kalman",
+      "name": "pNAtt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mNBaro": {
+      "__class__": "ParamTocElement",
+      "ident": 186,
+      "group": "kalman",
+      "name": "mNBaro",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mNGyro_rollpitch": {
+      "__class__": "ParamTocElement",
+      "ident": 187,
+      "group": "kalman",
+      "name": "mNGyro_rollpitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mNGyro_yaw": {
+      "__class__": "ParamTocElement",
+      "ident": 188,
+      "group": "kalman",
+      "name": "mNGyro_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "initialX": {
+      "__class__": "ParamTocElement",
+      "ident": 189,
+      "group": "kalman",
+      "name": "initialX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialY": {
+      "__class__": "ParamTocElement",
+      "ident": 190,
+      "group": "kalman",
+      "name": "initialY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialZ": {
+      "__class__": "ParamTocElement",
+      "ident": 191,
+      "group": "kalman",
+      "name": "initialZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 192,
+      "group": "kalman",
+      "name": "initialYaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxPos": {
+      "__class__": "ParamTocElement",
+      "ident": 193,
+      "group": "kalman",
+      "name": "maxPos",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxVel": {
+      "__class__": "ParamTocElement",
+      "ident": 194,
+      "group": "kalman",
+      "name": "maxVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "health": {
+    "startPropTest": {
+      "__class__": "ParamTocElement",
+      "ident": 195,
+      "group": "health",
+      "name": "startPropTest",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "startBatTest": {
+      "__class__": "ParamTocElement",
+      "ident": 196,
+      "group": "health",
+      "name": "startBatTest",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "propTestPWMRatio": {
+      "__class__": "ParamTocElement",
+      "ident": 197,
+      "group": "health",
+      "name": "propTestPWMRatio",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": true
+    },
+    "batTestPWMRatio": {
+      "__class__": "ParamTocElement",
+      "ident": 198,
+      "group": "health",
+      "name": "batTestPWMRatio",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "memTst": {
+    "resetW": {
+      "__class__": "ParamTocElement",
+      "ident": 199,
+      "group": "memTst",
+      "name": "resetW",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "posCtrlIndi": {
+    "K_xi_x": {
+      "__class__": "ParamTocElement",
+      "ident": 200,
+      "group": "posCtrlIndi",
+      "name": "K_xi_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_xi_y": {
+      "__class__": "ParamTocElement",
+      "ident": 201,
+      "group": "posCtrlIndi",
+      "name": "K_xi_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_xi_z": {
+      "__class__": "ParamTocElement",
+      "ident": 202,
+      "group": "posCtrlIndi",
+      "name": "K_xi_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_x": {
+      "__class__": "ParamTocElement",
+      "ident": 203,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_y": {
+      "__class__": "ParamTocElement",
+      "ident": 204,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_z": {
+      "__class__": "ParamTocElement",
+      "ident": 205,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pq_clamping": {
+      "__class__": "ParamTocElement",
+      "ident": 206,
+      "group": "posCtrlIndi",
+      "name": "pq_clamping",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "posCtlPid": {
+    "xKp": {
+      "__class__": "ParamTocElement",
+      "ident": 207,
+      "group": "posCtlPid",
+      "name": "xKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xKi": {
+      "__class__": "ParamTocElement",
+      "ident": 208,
+      "group": "posCtlPid",
+      "name": "xKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xKd": {
+      "__class__": "ParamTocElement",
+      "ident": 209,
+      "group": "posCtlPid",
+      "name": "xKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xKff": {
+      "__class__": "ParamTocElement",
+      "ident": 210,
+      "group": "posCtlPid",
+      "name": "xKff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKp": {
+      "__class__": "ParamTocElement",
+      "ident": 211,
+      "group": "posCtlPid",
+      "name": "yKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKi": {
+      "__class__": "ParamTocElement",
+      "ident": 212,
+      "group": "posCtlPid",
+      "name": "yKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKd": {
+      "__class__": "ParamTocElement",
+      "ident": 213,
+      "group": "posCtlPid",
+      "name": "yKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKff": {
+      "__class__": "ParamTocElement",
+      "ident": 214,
+      "group": "posCtlPid",
+      "name": "yKff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKp": {
+      "__class__": "ParamTocElement",
+      "ident": 215,
+      "group": "posCtlPid",
+      "name": "zKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKi": {
+      "__class__": "ParamTocElement",
+      "ident": 216,
+      "group": "posCtlPid",
+      "name": "zKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKd": {
+      "__class__": "ParamTocElement",
+      "ident": 217,
+      "group": "posCtlPid",
+      "name": "zKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKff": {
+      "__class__": "ParamTocElement",
+      "ident": 218,
+      "group": "posCtlPid",
+      "name": "zKff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "thrustBase": {
+      "__class__": "ParamTocElement",
+      "ident": 219,
+      "group": "posCtlPid",
+      "name": "thrustBase",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": true
+    },
+    "thrustMin": {
+      "__class__": "ParamTocElement",
+      "ident": 220,
+      "group": "posCtlPid",
+      "name": "thrustMin",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": true
+    },
+    "rLimit": {
+      "__class__": "ParamTocElement",
+      "ident": 221,
+      "group": "posCtlPid",
+      "name": "rLimit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pLimit": {
+      "__class__": "ParamTocElement",
+      "ident": 222,
+      "group": "posCtlPid",
+      "name": "pLimit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 223,
+      "group": "posCtlPid",
+      "name": "xVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 224,
+      "group": "posCtlPid",
+      "name": "yVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 225,
+      "group": "posCtlPid",
+      "name": "zVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "velCtlPid": {
+    "vxKp": {
+      "__class__": "ParamTocElement",
+      "ident": 226,
+      "group": "velCtlPid",
+      "name": "vxKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vxKi": {
+      "__class__": "ParamTocElement",
+      "ident": 227,
+      "group": "velCtlPid",
+      "name": "vxKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vxKd": {
+      "__class__": "ParamTocElement",
+      "ident": 228,
+      "group": "velCtlPid",
+      "name": "vxKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vxKFF": {
+      "__class__": "ParamTocElement",
+      "ident": 229,
+      "group": "velCtlPid",
+      "name": "vxKFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKp": {
+      "__class__": "ParamTocElement",
+      "ident": 230,
+      "group": "velCtlPid",
+      "name": "vyKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKi": {
+      "__class__": "ParamTocElement",
+      "ident": 231,
+      "group": "velCtlPid",
+      "name": "vyKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKd": {
+      "__class__": "ParamTocElement",
+      "ident": 232,
+      "group": "velCtlPid",
+      "name": "vyKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKFF": {
+      "__class__": "ParamTocElement",
+      "ident": 233,
+      "group": "velCtlPid",
+      "name": "vyKFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKp": {
+      "__class__": "ParamTocElement",
+      "ident": 234,
+      "group": "velCtlPid",
+      "name": "vzKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKi": {
+      "__class__": "ParamTocElement",
+      "ident": 235,
+      "group": "velCtlPid",
+      "name": "vzKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKd": {
+      "__class__": "ParamTocElement",
+      "ident": 236,
+      "group": "velCtlPid",
+      "name": "vzKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKFF": {
+      "__class__": "ParamTocElement",
+      "ident": 237,
+      "group": "velCtlPid",
+      "name": "vzKFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "posEstAlt": {
+    "estAlphaAsl": {
+      "__class__": "ParamTocElement",
+      "ident": 238,
+      "group": "posEstAlt",
+      "name": "estAlphaAsl",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "estAlphaZr": {
+      "__class__": "ParamTocElement",
+      "ident": 239,
+      "group": "posEstAlt",
+      "name": "estAlphaZr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "velFactor": {
+      "__class__": "ParamTocElement",
+      "ident": 240,
+      "group": "posEstAlt",
+      "name": "velFactor",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "velZAlpha": {
+      "__class__": "ParamTocElement",
+      "ident": 241,
+      "group": "posEstAlt",
+      "name": "velZAlpha",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vAccDeadband": {
+      "__class__": "ParamTocElement",
+      "ident": 242,
+      "group": "posEstAlt",
+      "name": "vAccDeadband",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "powerDist": {
+    "idleThrust": {
+      "__class__": "ParamTocElement",
+      "ident": 243,
+      "group": "powerDist",
+      "name": "idleThrust",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "quadSysId": {
+    "thrustToTorque": {
+      "__class__": "ParamTocElement",
+      "ident": 244,
+      "group": "quadSysId",
+      "name": "thrustToTorque",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pwmToThrustA": {
+      "__class__": "ParamTocElement",
+      "ident": 245,
+      "group": "quadSysId",
+      "name": "pwmToThrustA",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pwmToThrustB": {
+      "__class__": "ParamTocElement",
+      "ident": 246,
+      "group": "quadSysId",
+      "name": "pwmToThrustB",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "armLength": {
+      "__class__": "ParamTocElement",
+      "ident": 247,
+      "group": "quadSysId",
+      "name": "armLength",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "sensfusion6": {
+    "kp": {
+      "__class__": "ParamTocElement",
+      "ident": 248,
+      "group": "sensfusion6",
+      "name": "kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki": {
+      "__class__": "ParamTocElement",
+      "ident": 249,
+      "group": "sensfusion6",
+      "name": "ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "baseZacc": {
+      "__class__": "ParamTocElement",
+      "ident": 250,
+      "group": "sensfusion6",
+      "name": "baseZacc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "sound": {
+    "effect": {
+      "__class__": "ParamTocElement",
+      "ident": 251,
+      "group": "sound",
+      "name": "effect",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "neffect": {
+      "__class__": "ParamTocElement",
+      "ident": 252,
+      "group": "sound",
+      "name": "neffect",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "freq": {
+      "__class__": "ParamTocElement",
+      "ident": 253,
+      "group": "sound",
+      "name": "freq",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "stabilizer": {
+    "estimator": {
+      "__class__": "ParamTocElement",
+      "ident": 254,
+      "group": "stabilizer",
+      "name": "estimator",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "controller": {
+      "__class__": "ParamTocElement",
+      "ident": 255,
+      "group": "stabilizer",
+      "name": "controller",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stop": {
+      "__class__": "ParamTocElement",
+      "ident": 256,
+      "group": "stabilizer",
+      "name": "stop",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "cpu": {
+    "flash": {
+      "__class__": "ParamTocElement",
+      "ident": 257,
+      "group": "cpu",
+      "name": "flash",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "id0": {
+      "__class__": "ParamTocElement",
+      "ident": 258,
+      "group": "cpu",
+      "name": "id0",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "id1": {
+      "__class__": "ParamTocElement",
+      "ident": 259,
+      "group": "cpu",
+      "name": "id1",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "id2": {
+      "__class__": "ParamTocElement",
+      "ident": 260,
+      "group": "cpu",
+      "name": "id2",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "tdoaEngine": {
+    "logId": {
+      "__class__": "ParamTocElement",
+      "ident": 261,
+      "group": "tdoaEngine",
+      "name": "logId",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "logOthrId": {
+      "__class__": "ParamTocElement",
+      "ident": 262,
+      "group": "tdoaEngine",
+      "name": "logOthrId",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "matchAlgo": {
+      "__class__": "ParamTocElement",
+      "ident": 263,
+      "group": "tdoaEngine",
+      "name": "matchAlgo",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "lighthouse": {
+    "method": {
+      "__class__": "ParamTocElement",
+      "ident": 264,
+      "group": "lighthouse",
+      "name": "method",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "bsCalibReset": {
+      "__class__": "ParamTocElement",
+      "ident": 265,
+      "group": "lighthouse",
+      "name": "bsCalibReset",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "systemType": {
+      "__class__": "ParamTocElement",
+      "ident": 266,
+      "group": "lighthouse",
+      "name": "systemType",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "bsAvailable": {
+      "__class__": "ParamTocElement",
+      "ident": 267,
+      "group": "lighthouse",
+      "name": "bsAvailable",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "sweepStd": {
+      "__class__": "ParamTocElement",
+      "ident": 268,
+      "group": "lighthouse",
+      "name": "sweepStd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "sweepStd2": {
+      "__class__": "ParamTocElement",
+      "ident": 269,
+      "group": "lighthouse",
+      "name": "sweepStd2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "enLhRawStream": {
+      "__class__": "ParamTocElement",
+      "ident": 270,
+      "group": "lighthouse",
+      "name": "enLhRawStream",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "lh2maxRate": {
+      "__class__": "ParamTocElement",
+      "ident": 271,
+      "group": "lighthouse",
+      "name": "lh2maxRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "firmware": {
+    "revision0": {
+      "__class__": "ParamTocElement",
+      "ident": 272,
+      "group": "firmware",
+      "name": "revision0",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "revision1": {
+      "__class__": "ParamTocElement",
+      "ident": 273,
+      "group": "firmware",
+      "name": "revision1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "modified": {
+      "__class__": "ParamTocElement",
+      "ident": 274,
+      "group": "firmware",
+      "name": "modified",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  }
+}
\ No newline at end of file
diff --git a/crazyflie_demos/cache/C587C8AA.json b/crazyflie_demos/cache/C587C8AA.json
new file mode 100644
index 0000000000000000000000000000000000000000..57d13f9ddaefb45e19bd40412285e72b58b84738
--- /dev/null
+++ b/crazyflie_demos/cache/C587C8AA.json
@@ -0,0 +1,2326 @@
+{
+  "imu_sensors": {
+    "AK8963": {
+      "__class__": "ParamTocElement",
+      "ident": 0,
+      "group": "imu_sensors",
+      "name": "AK8963",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "LPS25H": {
+      "__class__": "ParamTocElement",
+      "ident": 1,
+      "group": "imu_sensors",
+      "name": "LPS25H",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "BMP388": {
+      "__class__": "ParamTocElement",
+      "ident": 5,
+      "group": "imu_sensors",
+      "name": "BMP388",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "imu_tests": {
+    "MPU6500": {
+      "__class__": "ParamTocElement",
+      "ident": 2,
+      "group": "imu_tests",
+      "name": "MPU6500",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "AK8963": {
+      "__class__": "ParamTocElement",
+      "ident": 3,
+      "group": "imu_tests",
+      "name": "AK8963",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "LPS25H": {
+      "__class__": "ParamTocElement",
+      "ident": 4,
+      "group": "imu_tests",
+      "name": "LPS25H",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "cpu": {
+    "flash": {
+      "__class__": "ParamTocElement",
+      "ident": 6,
+      "group": "cpu",
+      "name": "flash",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "id0": {
+      "__class__": "ParamTocElement",
+      "ident": 7,
+      "group": "cpu",
+      "name": "id0",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "id1": {
+      "__class__": "ParamTocElement",
+      "ident": 8,
+      "group": "cpu",
+      "name": "id1",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "id2": {
+      "__class__": "ParamTocElement",
+      "ident": 9,
+      "group": "cpu",
+      "name": "id2",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "system": {
+    "selftestPassed": {
+      "__class__": "ParamTocElement",
+      "ident": 10,
+      "group": "system",
+      "name": "selftestPassed",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 1,
+      "extended": false
+    },
+    "forceArm": {
+      "__class__": "ParamTocElement",
+      "ident": 11,
+      "group": "system",
+      "name": "forceArm",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0,
+      "extended": false
+    },
+    "taskDump": {
+      "__class__": "ParamTocElement",
+      "ident": 16,
+      "group": "system",
+      "name": "taskDump",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "highlight": {
+      "__class__": "ParamTocElement",
+      "ident": 187,
+      "group": "system",
+      "name": "highlight",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "crtpsrv": {
+    "echoDelay": {
+      "__class__": "ParamTocElement",
+      "ident": 12,
+      "group": "crtpsrv",
+      "name": "echoDelay",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "sound": {
+    "effect": {
+      "__class__": "ParamTocElement",
+      "ident": 13,
+      "group": "sound",
+      "name": "effect",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "neffect": {
+      "__class__": "ParamTocElement",
+      "ident": 14,
+      "group": "sound",
+      "name": "neffect",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "freq": {
+      "__class__": "ParamTocElement",
+      "ident": 15,
+      "group": "sound",
+      "name": "freq",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "memTst": {
+    "resetW": {
+      "__class__": "ParamTocElement",
+      "ident": 17,
+      "group": "memTst",
+      "name": "resetW",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "commander": {
+    "enHighLevel": {
+      "__class__": "ParamTocElement",
+      "ident": 18,
+      "group": "commander",
+      "name": "enHighLevel",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "flightmode": {
+    "althold": {
+      "__class__": "ParamTocElement",
+      "ident": 19,
+      "group": "flightmode",
+      "name": "althold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "poshold": {
+      "__class__": "ParamTocElement",
+      "ident": 20,
+      "group": "flightmode",
+      "name": "poshold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "posSet": {
+      "__class__": "ParamTocElement",
+      "ident": 21,
+      "group": "flightmode",
+      "name": "posSet",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "yawMode": {
+      "__class__": "ParamTocElement",
+      "ident": 22,
+      "group": "flightmode",
+      "name": "yawMode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModeRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 23,
+      "group": "flightmode",
+      "name": "stabModeRoll",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModePitch": {
+      "__class__": "ParamTocElement",
+      "ident": 24,
+      "group": "flightmode",
+      "name": "stabModePitch",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModeYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 25,
+      "group": "flightmode",
+      "name": "stabModeYaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "cmdrCPPM": {
+    "rateRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 26,
+      "group": "cmdrCPPM",
+      "name": "rateRoll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ratePitch": {
+      "__class__": "ParamTocElement",
+      "ident": 27,
+      "group": "cmdrCPPM",
+      "name": "ratePitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "angPitch": {
+      "__class__": "ParamTocElement",
+      "ident": 28,
+      "group": "cmdrCPPM",
+      "name": "angPitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "angRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 29,
+      "group": "cmdrCPPM",
+      "name": "angRoll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "rateYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 30,
+      "group": "cmdrCPPM",
+      "name": "rateYaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "locSrv": {
+    "enRangeStreamFP32": {
+      "__class__": "ParamTocElement",
+      "ident": 31,
+      "group": "locSrv",
+      "name": "enRangeStreamFP32",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "enLhAngleStream": {
+      "__class__": "ParamTocElement",
+      "ident": 32,
+      "group": "locSrv",
+      "name": "enLhAngleStream",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "extPosStdDev": {
+      "__class__": "ParamTocElement",
+      "ident": 33,
+      "group": "locSrv",
+      "name": "extPosStdDev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "extQuatStdDev": {
+      "__class__": "ParamTocElement",
+      "ident": 34,
+      "group": "locSrv",
+      "name": "extQuatStdDev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "pid_attitude": {
+    "roll_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 35,
+      "group": "pid_attitude",
+      "name": "roll_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "roll_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 36,
+      "group": "pid_attitude",
+      "name": "roll_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "roll_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 37,
+      "group": "pid_attitude",
+      "name": "roll_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pitch_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 38,
+      "group": "pid_attitude",
+      "name": "pitch_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pitch_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 39,
+      "group": "pid_attitude",
+      "name": "pitch_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pitch_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 40,
+      "group": "pid_attitude",
+      "name": "pitch_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yaw_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 41,
+      "group": "pid_attitude",
+      "name": "yaw_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yaw_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 42,
+      "group": "pid_attitude",
+      "name": "yaw_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yaw_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 43,
+      "group": "pid_attitude",
+      "name": "yaw_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "pid_rate": {
+    "roll_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 44,
+      "group": "pid_rate",
+      "name": "roll_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "roll_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 45,
+      "group": "pid_rate",
+      "name": "roll_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "roll_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 46,
+      "group": "pid_rate",
+      "name": "roll_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pitch_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 47,
+      "group": "pid_rate",
+      "name": "pitch_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pitch_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 48,
+      "group": "pid_rate",
+      "name": "pitch_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pitch_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 49,
+      "group": "pid_rate",
+      "name": "pitch_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yaw_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 50,
+      "group": "pid_rate",
+      "name": "yaw_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yaw_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 51,
+      "group": "pid_rate",
+      "name": "yaw_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yaw_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 52,
+      "group": "pid_rate",
+      "name": "yaw_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "sensfusion6": {
+    "kp": {
+      "__class__": "ParamTocElement",
+      "ident": 53,
+      "group": "sensfusion6",
+      "name": "kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ki": {
+      "__class__": "ParamTocElement",
+      "ident": 54,
+      "group": "sensfusion6",
+      "name": "ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "baseZacc": {
+      "__class__": "ParamTocElement",
+      "ident": 55,
+      "group": "sensfusion6",
+      "name": "baseZacc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "stabilizer": {
+    "estimator": {
+      "__class__": "ParamTocElement",
+      "ident": 56,
+      "group": "stabilizer",
+      "name": "estimator",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "controller": {
+      "__class__": "ParamTocElement",
+      "ident": 57,
+      "group": "stabilizer",
+      "name": "controller",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stop": {
+      "__class__": "ParamTocElement",
+      "ident": 58,
+      "group": "stabilizer",
+      "name": "stop",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "posEstAlt": {
+    "estAlphaAsl": {
+      "__class__": "ParamTocElement",
+      "ident": 59,
+      "group": "posEstAlt",
+      "name": "estAlphaAsl",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "estAlphaZr": {
+      "__class__": "ParamTocElement",
+      "ident": 60,
+      "group": "posEstAlt",
+      "name": "estAlphaZr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "velFactor": {
+      "__class__": "ParamTocElement",
+      "ident": 61,
+      "group": "posEstAlt",
+      "name": "velFactor",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "velZAlpha": {
+      "__class__": "ParamTocElement",
+      "ident": 62,
+      "group": "posEstAlt",
+      "name": "velZAlpha",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vAccDeadband": {
+      "__class__": "ParamTocElement",
+      "ident": 63,
+      "group": "posEstAlt",
+      "name": "vAccDeadband",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "posCtlPid": {
+    "xKp": {
+      "__class__": "ParamTocElement",
+      "ident": 64,
+      "group": "posCtlPid",
+      "name": "xKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "xKi": {
+      "__class__": "ParamTocElement",
+      "ident": 65,
+      "group": "posCtlPid",
+      "name": "xKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "xKd": {
+      "__class__": "ParamTocElement",
+      "ident": 66,
+      "group": "posCtlPid",
+      "name": "xKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yKp": {
+      "__class__": "ParamTocElement",
+      "ident": 67,
+      "group": "posCtlPid",
+      "name": "yKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yKi": {
+      "__class__": "ParamTocElement",
+      "ident": 68,
+      "group": "posCtlPid",
+      "name": "yKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "yKd": {
+      "__class__": "ParamTocElement",
+      "ident": 69,
+      "group": "posCtlPid",
+      "name": "yKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zKp": {
+      "__class__": "ParamTocElement",
+      "ident": 70,
+      "group": "posCtlPid",
+      "name": "zKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zKi": {
+      "__class__": "ParamTocElement",
+      "ident": 71,
+      "group": "posCtlPid",
+      "name": "zKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zKd": {
+      "__class__": "ParamTocElement",
+      "ident": 72,
+      "group": "posCtlPid",
+      "name": "zKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "thrustBase": {
+      "__class__": "ParamTocElement",
+      "ident": 73,
+      "group": "posCtlPid",
+      "name": "thrustBase",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "thrustMin": {
+      "__class__": "ParamTocElement",
+      "ident": 74,
+      "group": "posCtlPid",
+      "name": "thrustMin",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "rpLimit": {
+      "__class__": "ParamTocElement",
+      "ident": 75,
+      "group": "posCtlPid",
+      "name": "rpLimit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "xyVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 76,
+      "group": "posCtlPid",
+      "name": "xyVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 77,
+      "group": "posCtlPid",
+      "name": "zVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "velCtlPid": {
+    "vxKp": {
+      "__class__": "ParamTocElement",
+      "ident": 78,
+      "group": "velCtlPid",
+      "name": "vxKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vxKi": {
+      "__class__": "ParamTocElement",
+      "ident": 79,
+      "group": "velCtlPid",
+      "name": "vxKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vxKd": {
+      "__class__": "ParamTocElement",
+      "ident": 80,
+      "group": "velCtlPid",
+      "name": "vxKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vyKp": {
+      "__class__": "ParamTocElement",
+      "ident": 81,
+      "group": "velCtlPid",
+      "name": "vyKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vyKi": {
+      "__class__": "ParamTocElement",
+      "ident": 82,
+      "group": "velCtlPid",
+      "name": "vyKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vyKd": {
+      "__class__": "ParamTocElement",
+      "ident": 83,
+      "group": "velCtlPid",
+      "name": "vyKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vzKp": {
+      "__class__": "ParamTocElement",
+      "ident": 84,
+      "group": "velCtlPid",
+      "name": "vzKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vzKi": {
+      "__class__": "ParamTocElement",
+      "ident": 85,
+      "group": "velCtlPid",
+      "name": "vzKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vzKd": {
+      "__class__": "ParamTocElement",
+      "ident": 86,
+      "group": "velCtlPid",
+      "name": "vzKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "posCtrlIndi": {
+    "K_xi_x": {
+      "__class__": "ParamTocElement",
+      "ident": 87,
+      "group": "posCtrlIndi",
+      "name": "K_xi_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_xi_y": {
+      "__class__": "ParamTocElement",
+      "ident": 88,
+      "group": "posCtrlIndi",
+      "name": "K_xi_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_xi_z": {
+      "__class__": "ParamTocElement",
+      "ident": 89,
+      "group": "posCtrlIndi",
+      "name": "K_xi_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_x": {
+      "__class__": "ParamTocElement",
+      "ident": 90,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_y": {
+      "__class__": "ParamTocElement",
+      "ident": 91,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_z": {
+      "__class__": "ParamTocElement",
+      "ident": 92,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pq_clamping": {
+      "__class__": "ParamTocElement",
+      "ident": 93,
+      "group": "posCtrlIndi",
+      "name": "pq_clamping",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "controller": {
+    "tiltComp": {
+      "__class__": "ParamTocElement",
+      "ident": 94,
+      "group": "controller",
+      "name": "tiltComp",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ctrlMel": {
+    "kp_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 95,
+      "group": "ctrlMel",
+      "name": "kp_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kd_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 96,
+      "group": "ctrlMel",
+      "name": "kd_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ki_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 97,
+      "group": "ctrlMel",
+      "name": "ki_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "i_range_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 98,
+      "group": "ctrlMel",
+      "name": "i_range_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kp_z": {
+      "__class__": "ParamTocElement",
+      "ident": 99,
+      "group": "ctrlMel",
+      "name": "kp_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kd_z": {
+      "__class__": "ParamTocElement",
+      "ident": 100,
+      "group": "ctrlMel",
+      "name": "kd_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ki_z": {
+      "__class__": "ParamTocElement",
+      "ident": 101,
+      "group": "ctrlMel",
+      "name": "ki_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "i_range_z": {
+      "__class__": "ParamTocElement",
+      "ident": 102,
+      "group": "ctrlMel",
+      "name": "i_range_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "mass": {
+      "__class__": "ParamTocElement",
+      "ident": 103,
+      "group": "ctrlMel",
+      "name": "mass",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "massThrust": {
+      "__class__": "ParamTocElement",
+      "ident": 104,
+      "group": "ctrlMel",
+      "name": "massThrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kR_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 105,
+      "group": "ctrlMel",
+      "name": "kR_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kR_z": {
+      "__class__": "ParamTocElement",
+      "ident": 106,
+      "group": "ctrlMel",
+      "name": "kR_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kw_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 107,
+      "group": "ctrlMel",
+      "name": "kw_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kw_z": {
+      "__class__": "ParamTocElement",
+      "ident": 108,
+      "group": "ctrlMel",
+      "name": "kw_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ki_m_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 109,
+      "group": "ctrlMel",
+      "name": "ki_m_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ki_m_z": {
+      "__class__": "ParamTocElement",
+      "ident": 110,
+      "group": "ctrlMel",
+      "name": "ki_m_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "kd_omega_rp": {
+      "__class__": "ParamTocElement",
+      "ident": 111,
+      "group": "ctrlMel",
+      "name": "kd_omega_rp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "i_range_m_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 112,
+      "group": "ctrlMel",
+      "name": "i_range_m_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "i_range_m_z": {
+      "__class__": "ParamTocElement",
+      "ident": 113,
+      "group": "ctrlMel",
+      "name": "i_range_m_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ctrlINDI": {
+    "thrust_threshold": {
+      "__class__": "ParamTocElement",
+      "ident": 114,
+      "group": "ctrlINDI",
+      "name": "thrust_threshold",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bound_ctrl_input": {
+      "__class__": "ParamTocElement",
+      "ident": 115,
+      "group": "ctrlINDI",
+      "name": "bound_ctrl_input",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_p": {
+      "__class__": "ParamTocElement",
+      "ident": 116,
+      "group": "ctrlINDI",
+      "name": "g1_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_q": {
+      "__class__": "ParamTocElement",
+      "ident": 117,
+      "group": "ctrlINDI",
+      "name": "g1_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_r": {
+      "__class__": "ParamTocElement",
+      "ident": 118,
+      "group": "ctrlINDI",
+      "name": "g1_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g2": {
+      "__class__": "ParamTocElement",
+      "ident": 119,
+      "group": "ctrlINDI",
+      "name": "g2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_p": {
+      "__class__": "ParamTocElement",
+      "ident": 120,
+      "group": "ctrlINDI",
+      "name": "ref_err_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_q": {
+      "__class__": "ParamTocElement",
+      "ident": 121,
+      "group": "ctrlINDI",
+      "name": "ref_err_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_r": {
+      "__class__": "ParamTocElement",
+      "ident": 122,
+      "group": "ctrlINDI",
+      "name": "ref_err_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_p": {
+      "__class__": "ParamTocElement",
+      "ident": 123,
+      "group": "ctrlINDI",
+      "name": "ref_rate_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_q": {
+      "__class__": "ParamTocElement",
+      "ident": 124,
+      "group": "ctrlINDI",
+      "name": "ref_rate_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_r": {
+      "__class__": "ParamTocElement",
+      "ident": 125,
+      "group": "ctrlINDI",
+      "name": "ref_rate_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_p": {
+      "__class__": "ParamTocElement",
+      "ident": 126,
+      "group": "ctrlINDI",
+      "name": "act_dyn_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_q": {
+      "__class__": "ParamTocElement",
+      "ident": 127,
+      "group": "ctrlINDI",
+      "name": "act_dyn_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_r": {
+      "__class__": "ParamTocElement",
+      "ident": 128,
+      "group": "ctrlINDI",
+      "name": "act_dyn_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "filt_cutoff": {
+      "__class__": "ParamTocElement",
+      "ident": 129,
+      "group": "ctrlINDI",
+      "name": "filt_cutoff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "filt_cutoff_r": {
+      "__class__": "ParamTocElement",
+      "ident": 130,
+      "group": "ctrlINDI",
+      "name": "filt_cutoff_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "outerLoopActive": {
+      "__class__": "ParamTocElement",
+      "ident": 131,
+      "group": "ctrlINDI",
+      "name": "outerLoopActive",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "motorPowerSet": {
+    "enable": {
+      "__class__": "ParamTocElement",
+      "ident": 132,
+      "group": "motorPowerSet",
+      "name": "enable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "m1": {
+      "__class__": "ParamTocElement",
+      "ident": 133,
+      "group": "motorPowerSet",
+      "name": "m1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m2": {
+      "__class__": "ParamTocElement",
+      "ident": 134,
+      "group": "motorPowerSet",
+      "name": "m2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m3": {
+      "__class__": "ParamTocElement",
+      "ident": 135,
+      "group": "motorPowerSet",
+      "name": "m3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m4": {
+      "__class__": "ParamTocElement",
+      "ident": 136,
+      "group": "motorPowerSet",
+      "name": "m4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "powerDist": {
+    "idleThrust": {
+      "__class__": "ParamTocElement",
+      "ident": 137,
+      "group": "powerDist",
+      "name": "idleThrust",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "colAv": {
+    "enable": {
+      "__class__": "ParamTocElement",
+      "ident": 138,
+      "group": "colAv",
+      "name": "enable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidX": {
+      "__class__": "ParamTocElement",
+      "ident": 139,
+      "group": "colAv",
+      "name": "ellipsoidX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidY": {
+      "__class__": "ParamTocElement",
+      "ident": 140,
+      "group": "colAv",
+      "name": "ellipsoidY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidZ": {
+      "__class__": "ParamTocElement",
+      "ident": 141,
+      "group": "colAv",
+      "name": "ellipsoidZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinX": {
+      "__class__": "ParamTocElement",
+      "ident": 142,
+      "group": "colAv",
+      "name": "bboxMinX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinY": {
+      "__class__": "ParamTocElement",
+      "ident": 143,
+      "group": "colAv",
+      "name": "bboxMinY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinZ": {
+      "__class__": "ParamTocElement",
+      "ident": 144,
+      "group": "colAv",
+      "name": "bboxMinZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxX": {
+      "__class__": "ParamTocElement",
+      "ident": 145,
+      "group": "colAv",
+      "name": "bboxMaxX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxY": {
+      "__class__": "ParamTocElement",
+      "ident": 146,
+      "group": "colAv",
+      "name": "bboxMaxY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxZ": {
+      "__class__": "ParamTocElement",
+      "ident": 147,
+      "group": "colAv",
+      "name": "bboxMaxZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "horizon": {
+      "__class__": "ParamTocElement",
+      "ident": 148,
+      "group": "colAv",
+      "name": "horizon",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxSpeed": {
+      "__class__": "ParamTocElement",
+      "ident": 149,
+      "group": "colAv",
+      "name": "maxSpeed",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "sidestepThrsh": {
+      "__class__": "ParamTocElement",
+      "ident": 150,
+      "group": "colAv",
+      "name": "sidestepThrsh",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxPeerLocAge": {
+      "__class__": "ParamTocElement",
+      "ident": 151,
+      "group": "colAv",
+      "name": "maxPeerLocAge",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0,
+      "extended": false
+    },
+    "vorTol": {
+      "__class__": "ParamTocElement",
+      "ident": 152,
+      "group": "colAv",
+      "name": "vorTol",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vorIters": {
+      "__class__": "ParamTocElement",
+      "ident": 153,
+      "group": "colAv",
+      "name": "vorIters",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "health": {
+    "startPropTest": {
+      "__class__": "ParamTocElement",
+      "ident": 154,
+      "group": "health",
+      "name": "startPropTest",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "startBatTest": {
+      "__class__": "ParamTocElement",
+      "ident": 155,
+      "group": "health",
+      "name": "startBatTest",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "kalman": {
+    "resetEstimation": {
+      "__class__": "ParamTocElement",
+      "ident": 156,
+      "group": "kalman",
+      "name": "resetEstimation",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "quadIsFlying": {
+      "__class__": "ParamTocElement",
+      "ident": 157,
+      "group": "kalman",
+      "name": "quadIsFlying",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "robustTdoa": {
+      "__class__": "ParamTocElement",
+      "ident": 158,
+      "group": "kalman",
+      "name": "robustTdoa",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "robustTwr": {
+      "__class__": "ParamTocElement",
+      "ident": 159,
+      "group": "kalman",
+      "name": "robustTwr",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "pNAcc_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 160,
+      "group": "kalman",
+      "name": "pNAcc_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pNAcc_z": {
+      "__class__": "ParamTocElement",
+      "ident": 161,
+      "group": "kalman",
+      "name": "pNAcc_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pNVel": {
+      "__class__": "ParamTocElement",
+      "ident": 162,
+      "group": "kalman",
+      "name": "pNVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pNPos": {
+      "__class__": "ParamTocElement",
+      "ident": 163,
+      "group": "kalman",
+      "name": "pNPos",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pNAtt": {
+      "__class__": "ParamTocElement",
+      "ident": 164,
+      "group": "kalman",
+      "name": "pNAtt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "mNBaro": {
+      "__class__": "ParamTocElement",
+      "ident": 165,
+      "group": "kalman",
+      "name": "mNBaro",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "mNGyro_rollpitch": {
+      "__class__": "ParamTocElement",
+      "ident": 166,
+      "group": "kalman",
+      "name": "mNGyro_rollpitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "mNGyro_yaw": {
+      "__class__": "ParamTocElement",
+      "ident": 167,
+      "group": "kalman",
+      "name": "mNGyro_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialX": {
+      "__class__": "ParamTocElement",
+      "ident": 168,
+      "group": "kalman",
+      "name": "initialX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialY": {
+      "__class__": "ParamTocElement",
+      "ident": 169,
+      "group": "kalman",
+      "name": "initialY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialZ": {
+      "__class__": "ParamTocElement",
+      "ident": 170,
+      "group": "kalman",
+      "name": "initialZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 171,
+      "group": "kalman",
+      "name": "initialYaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxPos": {
+      "__class__": "ParamTocElement",
+      "ident": 172,
+      "group": "kalman",
+      "name": "maxPos",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxVel": {
+      "__class__": "ParamTocElement",
+      "ident": 173,
+      "group": "kalman",
+      "name": "maxVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "hlCommander": {
+    "vtoff": {
+      "__class__": "ParamTocElement",
+      "ident": 174,
+      "group": "hlCommander",
+      "name": "vtoff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vland": {
+      "__class__": "ParamTocElement",
+      "ident": 175,
+      "group": "hlCommander",
+      "name": "vland",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "deck": {
+    "bcLedRing": {
+      "__class__": "ParamTocElement",
+      "ident": 176,
+      "group": "deck",
+      "name": "bcLedRing",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcBuzzer": {
+      "__class__": "ParamTocElement",
+      "ident": 188,
+      "group": "deck",
+      "name": "bcBuzzer",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcGTGPS": {
+      "__class__": "ParamTocElement",
+      "ident": 189,
+      "group": "deck",
+      "name": "bcGTGPS",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcCPPM": {
+      "__class__": "ParamTocElement",
+      "ident": 190,
+      "group": "deck",
+      "name": "bcCPPM",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcUSD": {
+      "__class__": "ParamTocElement",
+      "ident": 191,
+      "group": "deck",
+      "name": "bcUSD",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcZRanger": {
+      "__class__": "ParamTocElement",
+      "ident": 194,
+      "group": "deck",
+      "name": "bcZRanger",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcZRanger2": {
+      "__class__": "ParamTocElement",
+      "ident": 195,
+      "group": "deck",
+      "name": "bcZRanger2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcDWM1000": {
+      "__class__": "ParamTocElement",
+      "ident": 196,
+      "group": "deck",
+      "name": "bcDWM1000",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcFlow": {
+      "__class__": "ParamTocElement",
+      "ident": 201,
+      "group": "deck",
+      "name": "bcFlow",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcFlow2": {
+      "__class__": "ParamTocElement",
+      "ident": 202,
+      "group": "deck",
+      "name": "bcFlow2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcOA": {
+      "__class__": "ParamTocElement",
+      "ident": 206,
+      "group": "deck",
+      "name": "bcOA",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcMultiranger": {
+      "__class__": "ParamTocElement",
+      "ident": 207,
+      "group": "deck",
+      "name": "bcMultiranger",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcLighthouse4": {
+      "__class__": "ParamTocElement",
+      "ident": 208,
+      "group": "deck",
+      "name": "bcLighthouse4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcActiveMarker": {
+      "__class__": "ParamTocElement",
+      "ident": 215,
+      "group": "deck",
+      "name": "bcActiveMarker",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcAIDeck": {
+      "__class__": "ParamTocElement",
+      "ident": 216,
+      "group": "deck",
+      "name": "bcAIDeck",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "ring": {
+    "effect": {
+      "__class__": "ParamTocElement",
+      "ident": 177,
+      "group": "ring",
+      "name": "effect",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "neffect": {
+      "__class__": "ParamTocElement",
+      "ident": 178,
+      "group": "ring",
+      "name": "neffect",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "solidRed": {
+      "__class__": "ParamTocElement",
+      "ident": 179,
+      "group": "ring",
+      "name": "solidRed",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "solidGreen": {
+      "__class__": "ParamTocElement",
+      "ident": 180,
+      "group": "ring",
+      "name": "solidGreen",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "solidBlue": {
+      "__class__": "ParamTocElement",
+      "ident": 181,
+      "group": "ring",
+      "name": "solidBlue",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "headlightEnable": {
+      "__class__": "ParamTocElement",
+      "ident": 182,
+      "group": "ring",
+      "name": "headlightEnable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "emptyCharge": {
+      "__class__": "ParamTocElement",
+      "ident": 183,
+      "group": "ring",
+      "name": "emptyCharge",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "fullCharge": {
+      "__class__": "ParamTocElement",
+      "ident": 184,
+      "group": "ring",
+      "name": "fullCharge",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "fadeColor": {
+      "__class__": "ParamTocElement",
+      "ident": 185,
+      "group": "ring",
+      "name": "fadeColor",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0,
+      "extended": false
+    },
+    "fadeTime": {
+      "__class__": "ParamTocElement",
+      "ident": 186,
+      "group": "ring",
+      "name": "fadeTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "usd": {
+    "canLog": {
+      "__class__": "ParamTocElement",
+      "ident": 192,
+      "group": "usd",
+      "name": "canLog",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "logging": {
+      "__class__": "ParamTocElement",
+      "ident": 193,
+      "group": "usd",
+      "name": "logging",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "loco": {
+    "mode": {
+      "__class__": "ParamTocElement",
+      "ident": 197,
+      "group": "loco",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "tdoaEngine": {
+    "logId": {
+      "__class__": "ParamTocElement",
+      "ident": 198,
+      "group": "tdoaEngine",
+      "name": "logId",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "logOthrId": {
+      "__class__": "ParamTocElement",
+      "ident": 199,
+      "group": "tdoaEngine",
+      "name": "logOthrId",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "matchAlgo": {
+      "__class__": "ParamTocElement",
+      "ident": 200,
+      "group": "tdoaEngine",
+      "name": "matchAlgo",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "motion": {
+    "disable": {
+      "__class__": "ParamTocElement",
+      "ident": 203,
+      "group": "motion",
+      "name": "disable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "adaptive": {
+      "__class__": "ParamTocElement",
+      "ident": 204,
+      "group": "motion",
+      "name": "adaptive",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "flowStdFixed": {
+      "__class__": "ParamTocElement",
+      "ident": 205,
+      "group": "motion",
+      "name": "flowStdFixed",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "activeMarker": {
+    "front": {
+      "__class__": "ParamTocElement",
+      "ident": 209,
+      "group": "activeMarker",
+      "name": "front",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "back": {
+      "__class__": "ParamTocElement",
+      "ident": 210,
+      "group": "activeMarker",
+      "name": "back",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "left": {
+      "__class__": "ParamTocElement",
+      "ident": 211,
+      "group": "activeMarker",
+      "name": "left",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "right": {
+      "__class__": "ParamTocElement",
+      "ident": 212,
+      "group": "activeMarker",
+      "name": "right",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "mode": {
+      "__class__": "ParamTocElement",
+      "ident": 213,
+      "group": "activeMarker",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "poll": {
+      "__class__": "ParamTocElement",
+      "ident": 214,
+      "group": "activeMarker",
+      "name": "poll",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "firmware": {
+    "revision0": {
+      "__class__": "ParamTocElement",
+      "ident": 217,
+      "group": "firmware",
+      "name": "revision0",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "revision1": {
+      "__class__": "ParamTocElement",
+      "ident": 218,
+      "group": "firmware",
+      "name": "revision1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "modified": {
+      "__class__": "ParamTocElement",
+      "ident": 219,
+      "group": "firmware",
+      "name": "modified",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "lighthouse": {
+    "method": {
+      "__class__": "ParamTocElement",
+      "ident": 220,
+      "group": "lighthouse",
+      "name": "method",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "bsCalibReset": {
+      "__class__": "ParamTocElement",
+      "ident": 221,
+      "group": "lighthouse",
+      "name": "bsCalibReset",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "systemType": {
+      "__class__": "ParamTocElement",
+      "ident": 222,
+      "group": "lighthouse",
+      "name": "systemType",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "sweepStd": {
+      "__class__": "ParamTocElement",
+      "ident": 223,
+      "group": "lighthouse",
+      "name": "sweepStd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "sweepStd2": {
+      "__class__": "ParamTocElement",
+      "ident": 224,
+      "group": "lighthouse",
+      "name": "sweepStd2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  }
+}
\ No newline at end of file
diff --git a/crazyflie_demos/cache/E03272BC.json b/crazyflie_demos/cache/E03272BC.json
new file mode 100644
index 0000000000000000000000000000000000000000..d445cd7b23b021f0b428b7c8b35da3762d853923
--- /dev/null
+++ b/crazyflie_demos/cache/E03272BC.json
@@ -0,0 +1,4348 @@
+{
+  "gyro": {
+    "xRaw": {
+      "__class__": "LogTocElement",
+      "ident": 0,
+      "group": "gyro",
+      "name": "xRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "yRaw": {
+      "__class__": "LogTocElement",
+      "ident": 1,
+      "group": "gyro",
+      "name": "yRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "zRaw": {
+      "__class__": "LogTocElement",
+      "ident": 2,
+      "group": "gyro",
+      "name": "zRaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "xVariance": {
+      "__class__": "LogTocElement",
+      "ident": 3,
+      "group": "gyro",
+      "name": "xVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yVariance": {
+      "__class__": "LogTocElement",
+      "ident": 4,
+      "group": "gyro",
+      "name": "yVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zVariance": {
+      "__class__": "LogTocElement",
+      "ident": 5,
+      "group": "gyro",
+      "name": "zVariance",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 108,
+      "group": "gyro",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 109,
+      "group": "gyro",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 110,
+      "group": "gyro",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "pwm": {
+    "m1_pwm": {
+      "__class__": "LogTocElement",
+      "ident": 6,
+      "group": "pwm",
+      "name": "m1_pwm",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m2_pwm": {
+      "__class__": "LogTocElement",
+      "ident": 7,
+      "group": "pwm",
+      "name": "m2_pwm",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m3_pwm": {
+      "__class__": "LogTocElement",
+      "ident": 8,
+      "group": "pwm",
+      "name": "m3_pwm",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m4_pwm": {
+      "__class__": "LogTocElement",
+      "ident": 9,
+      "group": "pwm",
+      "name": "m4_pwm",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "crtp": {
+    "rxRate": {
+      "__class__": "LogTocElement",
+      "ident": 10,
+      "group": "crtp",
+      "name": "rxRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "txRate": {
+      "__class__": "LogTocElement",
+      "ident": 11,
+      "group": "crtp",
+      "name": "txRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "pm": {
+    "vbat": {
+      "__class__": "LogTocElement",
+      "ident": 12,
+      "group": "pm",
+      "name": "vbat",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vbatMV": {
+      "__class__": "LogTocElement",
+      "ident": 13,
+      "group": "pm",
+      "name": "vbatMV",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "extVbat": {
+      "__class__": "LogTocElement",
+      "ident": 14,
+      "group": "pm",
+      "name": "extVbat",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "extVbatMV": {
+      "__class__": "LogTocElement",
+      "ident": 15,
+      "group": "pm",
+      "name": "extVbatMV",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "extCurr": {
+      "__class__": "LogTocElement",
+      "ident": 16,
+      "group": "pm",
+      "name": "extCurr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "chargeCurrent": {
+      "__class__": "LogTocElement",
+      "ident": 17,
+      "group": "pm",
+      "name": "chargeCurrent",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "state": {
+      "__class__": "LogTocElement",
+      "ident": 18,
+      "group": "pm",
+      "name": "state",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0
+    },
+    "batteryLevel": {
+      "__class__": "LogTocElement",
+      "ident": 19,
+      "group": "pm",
+      "name": "batteryLevel",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "radio": {
+    "rssi": {
+      "__class__": "LogTocElement",
+      "ident": 20,
+      "group": "radio",
+      "name": "rssi",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isConnected": {
+      "__class__": "LogTocElement",
+      "ident": 21,
+      "group": "radio",
+      "name": "isConnected",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "sys": {
+    "armed": {
+      "__class__": "LogTocElement",
+      "ident": 22,
+      "group": "sys",
+      "name": "armed",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0
+    },
+    "canfly": {
+      "__class__": "LogTocElement",
+      "ident": 38,
+      "group": "sys",
+      "name": "canfly",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isFlying": {
+      "__class__": "LogTocElement",
+      "ident": 39,
+      "group": "sys",
+      "name": "isFlying",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isTumbled": {
+      "__class__": "LogTocElement",
+      "ident": 40,
+      "group": "sys",
+      "name": "isTumbled",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "extrx": {
+    "ch0": {
+      "__class__": "LogTocElement",
+      "ident": 23,
+      "group": "extrx",
+      "name": "ch0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch1": {
+      "__class__": "LogTocElement",
+      "ident": 24,
+      "group": "extrx",
+      "name": "ch1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch2": {
+      "__class__": "LogTocElement",
+      "ident": 25,
+      "group": "extrx",
+      "name": "ch2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "ch3": {
+      "__class__": "LogTocElement",
+      "ident": 26,
+      "group": "extrx",
+      "name": "ch3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "thrust": {
+      "__class__": "LogTocElement",
+      "ident": 27,
+      "group": "extrx",
+      "name": "thrust",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 28,
+      "group": "extrx",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 29,
+      "group": "extrx",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 30,
+      "group": "extrx",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "memTst": {
+    "errCntW": {
+      "__class__": "LogTocElement",
+      "ident": 31,
+      "group": "memTst",
+      "name": "errCntW",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "range": {
+    "front": {
+      "__class__": "LogTocElement",
+      "ident": 32,
+      "group": "range",
+      "name": "front",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "back": {
+      "__class__": "LogTocElement",
+      "ident": 33,
+      "group": "range",
+      "name": "back",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "up": {
+      "__class__": "LogTocElement",
+      "ident": 34,
+      "group": "range",
+      "name": "up",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "left": {
+      "__class__": "LogTocElement",
+      "ident": 35,
+      "group": "range",
+      "name": "left",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "right": {
+      "__class__": "LogTocElement",
+      "ident": 36,
+      "group": "range",
+      "name": "right",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "zrange": {
+      "__class__": "LogTocElement",
+      "ident": 37,
+      "group": "range",
+      "name": "zrange",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "ext_pos": {
+    "X": {
+      "__class__": "LogTocElement",
+      "ident": 41,
+      "group": "ext_pos",
+      "name": "X",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Y": {
+      "__class__": "LogTocElement",
+      "ident": 42,
+      "group": "ext_pos",
+      "name": "Y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Z": {
+      "__class__": "LogTocElement",
+      "ident": 43,
+      "group": "ext_pos",
+      "name": "Z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "locSrv": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 44,
+      "group": "locSrv",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 45,
+      "group": "locSrv",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 46,
+      "group": "locSrv",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 47,
+      "group": "locSrv",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 48,
+      "group": "locSrv",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 49,
+      "group": "locSrv",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 50,
+      "group": "locSrv",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "locSrvZ": {
+    "tick": {
+      "__class__": "LogTocElement",
+      "ident": 51,
+      "group": "locSrvZ",
+      "name": "tick",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "pid_attitude": {
+    "roll_outP": {
+      "__class__": "LogTocElement",
+      "ident": 52,
+      "group": "pid_attitude",
+      "name": "roll_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outI": {
+      "__class__": "LogTocElement",
+      "ident": 53,
+      "group": "pid_attitude",
+      "name": "roll_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outD": {
+      "__class__": "LogTocElement",
+      "ident": 54,
+      "group": "pid_attitude",
+      "name": "roll_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outP": {
+      "__class__": "LogTocElement",
+      "ident": 55,
+      "group": "pid_attitude",
+      "name": "pitch_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outI": {
+      "__class__": "LogTocElement",
+      "ident": 56,
+      "group": "pid_attitude",
+      "name": "pitch_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outD": {
+      "__class__": "LogTocElement",
+      "ident": 57,
+      "group": "pid_attitude",
+      "name": "pitch_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outP": {
+      "__class__": "LogTocElement",
+      "ident": 58,
+      "group": "pid_attitude",
+      "name": "yaw_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outI": {
+      "__class__": "LogTocElement",
+      "ident": 59,
+      "group": "pid_attitude",
+      "name": "yaw_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outD": {
+      "__class__": "LogTocElement",
+      "ident": 60,
+      "group": "pid_attitude",
+      "name": "yaw_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "pid_rate": {
+    "roll_outP": {
+      "__class__": "LogTocElement",
+      "ident": 61,
+      "group": "pid_rate",
+      "name": "roll_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outI": {
+      "__class__": "LogTocElement",
+      "ident": 62,
+      "group": "pid_rate",
+      "name": "roll_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll_outD": {
+      "__class__": "LogTocElement",
+      "ident": 63,
+      "group": "pid_rate",
+      "name": "roll_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outP": {
+      "__class__": "LogTocElement",
+      "ident": 64,
+      "group": "pid_rate",
+      "name": "pitch_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outI": {
+      "__class__": "LogTocElement",
+      "ident": 65,
+      "group": "pid_rate",
+      "name": "pitch_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch_outD": {
+      "__class__": "LogTocElement",
+      "ident": 66,
+      "group": "pid_rate",
+      "name": "pitch_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outP": {
+      "__class__": "LogTocElement",
+      "ident": 67,
+      "group": "pid_rate",
+      "name": "yaw_outP",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outI": {
+      "__class__": "LogTocElement",
+      "ident": 68,
+      "group": "pid_rate",
+      "name": "yaw_outI",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw_outD": {
+      "__class__": "LogTocElement",
+      "ident": 69,
+      "group": "pid_rate",
+      "name": "yaw_outD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "sensfusion6": {
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 70,
+      "group": "sensfusion6",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 71,
+      "group": "sensfusion6",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 72,
+      "group": "sensfusion6",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 73,
+      "group": "sensfusion6",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityX": {
+      "__class__": "LogTocElement",
+      "ident": 74,
+      "group": "sensfusion6",
+      "name": "gravityX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityY": {
+      "__class__": "LogTocElement",
+      "ident": 75,
+      "group": "sensfusion6",
+      "name": "gravityY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "gravityZ": {
+      "__class__": "LogTocElement",
+      "ident": 76,
+      "group": "sensfusion6",
+      "name": "gravityZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accZbase": {
+      "__class__": "LogTocElement",
+      "ident": 77,
+      "group": "sensfusion6",
+      "name": "accZbase",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "isInit": {
+      "__class__": "LogTocElement",
+      "ident": 78,
+      "group": "sensfusion6",
+      "name": "isInit",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "isCalibrated": {
+      "__class__": "LogTocElement",
+      "ident": 79,
+      "group": "sensfusion6",
+      "name": "isCalibrated",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "acc": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 80,
+      "group": "acc",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 81,
+      "group": "acc",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 82,
+      "group": "acc",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "baro": {
+    "asl": {
+      "__class__": "LogTocElement",
+      "ident": 83,
+      "group": "baro",
+      "name": "asl",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "temp": {
+      "__class__": "LogTocElement",
+      "ident": 84,
+      "group": "baro",
+      "name": "temp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure": {
+      "__class__": "LogTocElement",
+      "ident": 85,
+      "group": "baro",
+      "name": "pressure",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "controller": {
+    "ctr_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 86,
+      "group": "controller",
+      "name": "ctr_yaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 213,
+      "group": "controller",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 214,
+      "group": "controller",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 215,
+      "group": "controller",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 216,
+      "group": "controller",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 217,
+      "group": "controller",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 218,
+      "group": "controller",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 219,
+      "group": "controller",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accelz": {
+      "__class__": "LogTocElement",
+      "ident": 220,
+      "group": "controller",
+      "name": "accelz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "actuatorThrust": {
+      "__class__": "LogTocElement",
+      "ident": 221,
+      "group": "controller",
+      "name": "actuatorThrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 222,
+      "group": "controller",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 223,
+      "group": "controller",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 224,
+      "group": "controller",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rollRate": {
+      "__class__": "LogTocElement",
+      "ident": 225,
+      "group": "controller",
+      "name": "rollRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitchRate": {
+      "__class__": "LogTocElement",
+      "ident": 226,
+      "group": "controller",
+      "name": "pitchRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yawRate": {
+      "__class__": "LogTocElement",
+      "ident": 227,
+      "group": "controller",
+      "name": "yawRate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrltarget": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 87,
+      "group": "ctrltarget",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 88,
+      "group": "ctrltarget",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 89,
+      "group": "ctrltarget",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 90,
+      "group": "ctrltarget",
+      "name": "vx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 91,
+      "group": "ctrltarget",
+      "name": "vy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 92,
+      "group": "ctrltarget",
+      "name": "vz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 93,
+      "group": "ctrltarget",
+      "name": "ax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 94,
+      "group": "ctrltarget",
+      "name": "ay",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 95,
+      "group": "ctrltarget",
+      "name": "az",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 96,
+      "group": "ctrltarget",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 97,
+      "group": "ctrltarget",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 98,
+      "group": "ctrltarget",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrltargetZ": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 99,
+      "group": "ctrltargetZ",
+      "name": "x",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 100,
+      "group": "ctrltargetZ",
+      "name": "y",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 101,
+      "group": "ctrltargetZ",
+      "name": "z",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 102,
+      "group": "ctrltargetZ",
+      "name": "vx",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 103,
+      "group": "ctrltargetZ",
+      "name": "vy",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 104,
+      "group": "ctrltargetZ",
+      "name": "vz",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 105,
+      "group": "ctrltargetZ",
+      "name": "ax",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 106,
+      "group": "ctrltargetZ",
+      "name": "ay",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 107,
+      "group": "ctrltargetZ",
+      "name": "az",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "mag": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 111,
+      "group": "mag",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 112,
+      "group": "mag",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 113,
+      "group": "mag",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "stabilizer": {
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 114,
+      "group": "stabilizer",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 115,
+      "group": "stabilizer",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 116,
+      "group": "stabilizer",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "thrust": {
+      "__class__": "LogTocElement",
+      "ident": 117,
+      "group": "stabilizer",
+      "name": "thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtStab": {
+      "__class__": "LogTocElement",
+      "ident": 118,
+      "group": "stabilizer",
+      "name": "rtStab",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "intToOut": {
+      "__class__": "LogTocElement",
+      "ident": 119,
+      "group": "stabilizer",
+      "name": "intToOut",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "stateEstimate": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 120,
+      "group": "stateEstimate",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 121,
+      "group": "stateEstimate",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 122,
+      "group": "stateEstimate",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 123,
+      "group": "stateEstimate",
+      "name": "vx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 124,
+      "group": "stateEstimate",
+      "name": "vy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 125,
+      "group": "stateEstimate",
+      "name": "vz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 126,
+      "group": "stateEstimate",
+      "name": "ax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 127,
+      "group": "stateEstimate",
+      "name": "ay",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 128,
+      "group": "stateEstimate",
+      "name": "az",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "roll": {
+      "__class__": "LogTocElement",
+      "ident": 129,
+      "group": "stateEstimate",
+      "name": "roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pitch": {
+      "__class__": "LogTocElement",
+      "ident": 130,
+      "group": "stateEstimate",
+      "name": "pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "yaw": {
+      "__class__": "LogTocElement",
+      "ident": 131,
+      "group": "stateEstimate",
+      "name": "yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qx": {
+      "__class__": "LogTocElement",
+      "ident": 132,
+      "group": "stateEstimate",
+      "name": "qx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qy": {
+      "__class__": "LogTocElement",
+      "ident": 133,
+      "group": "stateEstimate",
+      "name": "qy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qz": {
+      "__class__": "LogTocElement",
+      "ident": 134,
+      "group": "stateEstimate",
+      "name": "qz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "qw": {
+      "__class__": "LogTocElement",
+      "ident": 135,
+      "group": "stateEstimate",
+      "name": "qw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "stateEstimateZ": {
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 136,
+      "group": "stateEstimateZ",
+      "name": "x",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 137,
+      "group": "stateEstimateZ",
+      "name": "y",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 138,
+      "group": "stateEstimateZ",
+      "name": "z",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vx": {
+      "__class__": "LogTocElement",
+      "ident": 139,
+      "group": "stateEstimateZ",
+      "name": "vx",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vy": {
+      "__class__": "LogTocElement",
+      "ident": 140,
+      "group": "stateEstimateZ",
+      "name": "vy",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "vz": {
+      "__class__": "LogTocElement",
+      "ident": 141,
+      "group": "stateEstimateZ",
+      "name": "vz",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ax": {
+      "__class__": "LogTocElement",
+      "ident": 142,
+      "group": "stateEstimateZ",
+      "name": "ax",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ay": {
+      "__class__": "LogTocElement",
+      "ident": 143,
+      "group": "stateEstimateZ",
+      "name": "ay",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "az": {
+      "__class__": "LogTocElement",
+      "ident": 144,
+      "group": "stateEstimateZ",
+      "name": "az",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "quat": {
+      "__class__": "LogTocElement",
+      "ident": 145,
+      "group": "stateEstimateZ",
+      "name": "quat",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "rateRoll": {
+      "__class__": "LogTocElement",
+      "ident": 146,
+      "group": "stateEstimateZ",
+      "name": "rateRoll",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "ratePitch": {
+      "__class__": "LogTocElement",
+      "ident": 147,
+      "group": "stateEstimateZ",
+      "name": "ratePitch",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "rateYaw": {
+      "__class__": "LogTocElement",
+      "ident": 148,
+      "group": "stateEstimateZ",
+      "name": "rateYaw",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    }
+  },
+  "posEstAlt": {
+    "estimatedZ": {
+      "__class__": "LogTocElement",
+      "ident": 149,
+      "group": "posEstAlt",
+      "name": "estimatedZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estVZ": {
+      "__class__": "LogTocElement",
+      "ident": 150,
+      "group": "posEstAlt",
+      "name": "estVZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velocityZ": {
+      "__class__": "LogTocElement",
+      "ident": 151,
+      "group": "posEstAlt",
+      "name": "velocityZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "posCtl": {
+    "targetVX": {
+      "__class__": "LogTocElement",
+      "ident": 152,
+      "group": "posCtl",
+      "name": "targetVX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetVY": {
+      "__class__": "LogTocElement",
+      "ident": 153,
+      "group": "posCtl",
+      "name": "targetVY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetVZ": {
+      "__class__": "LogTocElement",
+      "ident": 154,
+      "group": "posCtl",
+      "name": "targetVZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetX": {
+      "__class__": "LogTocElement",
+      "ident": 155,
+      "group": "posCtl",
+      "name": "targetX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetY": {
+      "__class__": "LogTocElement",
+      "ident": 156,
+      "group": "posCtl",
+      "name": "targetY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "targetZ": {
+      "__class__": "LogTocElement",
+      "ident": 157,
+      "group": "posCtl",
+      "name": "targetZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xp": {
+      "__class__": "LogTocElement",
+      "ident": 158,
+      "group": "posCtl",
+      "name": "Xp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xi": {
+      "__class__": "LogTocElement",
+      "ident": 159,
+      "group": "posCtl",
+      "name": "Xi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Xd": {
+      "__class__": "LogTocElement",
+      "ident": 160,
+      "group": "posCtl",
+      "name": "Xd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yp": {
+      "__class__": "LogTocElement",
+      "ident": 161,
+      "group": "posCtl",
+      "name": "Yp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yi": {
+      "__class__": "LogTocElement",
+      "ident": 162,
+      "group": "posCtl",
+      "name": "Yi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Yd": {
+      "__class__": "LogTocElement",
+      "ident": 163,
+      "group": "posCtl",
+      "name": "Yd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zp": {
+      "__class__": "LogTocElement",
+      "ident": 164,
+      "group": "posCtl",
+      "name": "Zp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zi": {
+      "__class__": "LogTocElement",
+      "ident": 165,
+      "group": "posCtl",
+      "name": "Zi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Zd": {
+      "__class__": "LogTocElement",
+      "ident": 166,
+      "group": "posCtl",
+      "name": "Zd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXp": {
+      "__class__": "LogTocElement",
+      "ident": 167,
+      "group": "posCtl",
+      "name": "VXp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXi": {
+      "__class__": "LogTocElement",
+      "ident": 168,
+      "group": "posCtl",
+      "name": "VXi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VXd": {
+      "__class__": "LogTocElement",
+      "ident": 169,
+      "group": "posCtl",
+      "name": "VXd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZp": {
+      "__class__": "LogTocElement",
+      "ident": 170,
+      "group": "posCtl",
+      "name": "VZp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZi": {
+      "__class__": "LogTocElement",
+      "ident": 171,
+      "group": "posCtl",
+      "name": "VZi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "VZd": {
+      "__class__": "LogTocElement",
+      "ident": 172,
+      "group": "posCtl",
+      "name": "VZd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "posCtrlIndi": {
+    "posRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 173,
+      "group": "posCtrlIndi",
+      "name": "posRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "posRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 174,
+      "group": "posCtrlIndi",
+      "name": "posRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "posRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 175,
+      "group": "posCtrlIndi",
+      "name": "posRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_x": {
+      "__class__": "LogTocElement",
+      "ident": 176,
+      "group": "posCtrlIndi",
+      "name": "velS_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_y": {
+      "__class__": "LogTocElement",
+      "ident": 177,
+      "group": "posCtrlIndi",
+      "name": "velS_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velS_z": {
+      "__class__": "LogTocElement",
+      "ident": 178,
+      "group": "posCtrlIndi",
+      "name": "velS_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 179,
+      "group": "posCtrlIndi",
+      "name": "velRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 180,
+      "group": "posCtrlIndi",
+      "name": "velRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "velRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 181,
+      "group": "posCtrlIndi",
+      "name": "velRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_roll": {
+      "__class__": "LogTocElement",
+      "ident": 182,
+      "group": "posCtrlIndi",
+      "name": "angS_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 183,
+      "group": "posCtrlIndi",
+      "name": "angS_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angS_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 184,
+      "group": "posCtrlIndi",
+      "name": "angS_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_roll": {
+      "__class__": "LogTocElement",
+      "ident": 185,
+      "group": "posCtrlIndi",
+      "name": "angF_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 186,
+      "group": "posCtrlIndi",
+      "name": "angF_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angF_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 187,
+      "group": "posCtrlIndi",
+      "name": "angF_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_x": {
+      "__class__": "LogTocElement",
+      "ident": 188,
+      "group": "posCtrlIndi",
+      "name": "accRef_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_y": {
+      "__class__": "LogTocElement",
+      "ident": 189,
+      "group": "posCtrlIndi",
+      "name": "accRef_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accRef_z": {
+      "__class__": "LogTocElement",
+      "ident": 190,
+      "group": "posCtrlIndi",
+      "name": "accRef_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_x": {
+      "__class__": "LogTocElement",
+      "ident": 191,
+      "group": "posCtrlIndi",
+      "name": "accS_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_y": {
+      "__class__": "LogTocElement",
+      "ident": 192,
+      "group": "posCtrlIndi",
+      "name": "accS_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accS_z": {
+      "__class__": "LogTocElement",
+      "ident": 193,
+      "group": "posCtrlIndi",
+      "name": "accS_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_x": {
+      "__class__": "LogTocElement",
+      "ident": 194,
+      "group": "posCtrlIndi",
+      "name": "accF_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_y": {
+      "__class__": "LogTocElement",
+      "ident": 195,
+      "group": "posCtrlIndi",
+      "name": "accF_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accF_z": {
+      "__class__": "LogTocElement",
+      "ident": 196,
+      "group": "posCtrlIndi",
+      "name": "accF_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_x": {
+      "__class__": "LogTocElement",
+      "ident": 197,
+      "group": "posCtrlIndi",
+      "name": "accFT_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_y": {
+      "__class__": "LogTocElement",
+      "ident": 198,
+      "group": "posCtrlIndi",
+      "name": "accFT_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accFT_z": {
+      "__class__": "LogTocElement",
+      "ident": 199,
+      "group": "posCtrlIndi",
+      "name": "accFT_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_x": {
+      "__class__": "LogTocElement",
+      "ident": 200,
+      "group": "posCtrlIndi",
+      "name": "accErr_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_y": {
+      "__class__": "LogTocElement",
+      "ident": 201,
+      "group": "posCtrlIndi",
+      "name": "accErr_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accErr_z": {
+      "__class__": "LogTocElement",
+      "ident": 202,
+      "group": "posCtrlIndi",
+      "name": "accErr_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "phi_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 203,
+      "group": "posCtrlIndi",
+      "name": "phi_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "theta_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 204,
+      "group": "posCtrlIndi",
+      "name": "theta_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_tilde": {
+      "__class__": "LogTocElement",
+      "ident": 205,
+      "group": "posCtrlIndi",
+      "name": "T_tilde",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_inner": {
+      "__class__": "LogTocElement",
+      "ident": 206,
+      "group": "posCtrlIndi",
+      "name": "T_inner",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_inner_f": {
+      "__class__": "LogTocElement",
+      "ident": 207,
+      "group": "posCtrlIndi",
+      "name": "T_inner_f",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "T_incremented": {
+      "__class__": "LogTocElement",
+      "ident": 208,
+      "group": "posCtrlIndi",
+      "name": "T_incremented",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_phi": {
+      "__class__": "LogTocElement",
+      "ident": 209,
+      "group": "posCtrlIndi",
+      "name": "cmd_phi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_theta": {
+      "__class__": "LogTocElement",
+      "ident": 210,
+      "group": "posCtrlIndi",
+      "name": "cmd_theta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "estimator": {
+    "rtApnd": {
+      "__class__": "LogTocElement",
+      "ident": 211,
+      "group": "estimator",
+      "name": "rtApnd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtRej": {
+      "__class__": "LogTocElement",
+      "ident": 212,
+      "group": "estimator",
+      "name": "rtRej",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrlMel": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 228,
+      "group": "ctrlMel",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 229,
+      "group": "ctrlMel",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 230,
+      "group": "ctrlMel",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 231,
+      "group": "ctrlMel",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 232,
+      "group": "ctrlMel",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 233,
+      "group": "ctrlMel",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 234,
+      "group": "ctrlMel",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "accelz": {
+      "__class__": "LogTocElement",
+      "ident": 235,
+      "group": "ctrlMel",
+      "name": "accelz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdx": {
+      "__class__": "LogTocElement",
+      "ident": 236,
+      "group": "ctrlMel",
+      "name": "zdx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdy": {
+      "__class__": "LogTocElement",
+      "ident": 237,
+      "group": "ctrlMel",
+      "name": "zdy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "zdz": {
+      "__class__": "LogTocElement",
+      "ident": 238,
+      "group": "ctrlMel",
+      "name": "zdz",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_x": {
+      "__class__": "LogTocElement",
+      "ident": 239,
+      "group": "ctrlMel",
+      "name": "i_err_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_y": {
+      "__class__": "LogTocElement",
+      "ident": 240,
+      "group": "ctrlMel",
+      "name": "i_err_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "i_err_z": {
+      "__class__": "LogTocElement",
+      "ident": 241,
+      "group": "ctrlMel",
+      "name": "i_err_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ctrlINDI": {
+    "cmd_thrust": {
+      "__class__": "LogTocElement",
+      "ident": 242,
+      "group": "ctrlINDI",
+      "name": "cmd_thrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_roll": {
+      "__class__": "LogTocElement",
+      "ident": 243,
+      "group": "ctrlINDI",
+      "name": "cmd_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 244,
+      "group": "ctrlINDI",
+      "name": "cmd_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cmd_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 245,
+      "group": "ctrlINDI",
+      "name": "cmd_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_roll": {
+      "__class__": "LogTocElement",
+      "ident": 246,
+      "group": "ctrlINDI",
+      "name": "r_roll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_pitch": {
+      "__class__": "LogTocElement",
+      "ident": 247,
+      "group": "ctrlINDI",
+      "name": "r_pitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "r_yaw": {
+      "__class__": "LogTocElement",
+      "ident": 248,
+      "group": "ctrlINDI",
+      "name": "r_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_p": {
+      "__class__": "LogTocElement",
+      "ident": 249,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_q": {
+      "__class__": "LogTocElement",
+      "ident": 250,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "u_act_dyn_r": {
+      "__class__": "LogTocElement",
+      "ident": 251,
+      "group": "ctrlINDI",
+      "name": "u_act_dyn_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_p": {
+      "__class__": "LogTocElement",
+      "ident": 252,
+      "group": "ctrlINDI",
+      "name": "du_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_q": {
+      "__class__": "LogTocElement",
+      "ident": 253,
+      "group": "ctrlINDI",
+      "name": "du_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "du_r": {
+      "__class__": "LogTocElement",
+      "ident": 254,
+      "group": "ctrlINDI",
+      "name": "du_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_p": {
+      "__class__": "LogTocElement",
+      "ident": 255,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_q": {
+      "__class__": "LogTocElement",
+      "ident": 256,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "ang_accel_ref_r": {
+      "__class__": "LogTocElement",
+      "ident": 257,
+      "group": "ctrlINDI",
+      "name": "ang_accel_ref_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[0]": {
+      "__class__": "LogTocElement",
+      "ident": 258,
+      "group": "ctrlINDI",
+      "name": "rate_d[0]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[1]": {
+      "__class__": "LogTocElement",
+      "ident": 259,
+      "group": "ctrlINDI",
+      "name": "rate_d[1]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rate_d[2]": {
+      "__class__": "LogTocElement",
+      "ident": 260,
+      "group": "ctrlINDI",
+      "name": "rate_d[2]",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_p": {
+      "__class__": "LogTocElement",
+      "ident": 261,
+      "group": "ctrlINDI",
+      "name": "uf_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_q": {
+      "__class__": "LogTocElement",
+      "ident": 262,
+      "group": "ctrlINDI",
+      "name": "uf_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "uf_r": {
+      "__class__": "LogTocElement",
+      "ident": 263,
+      "group": "ctrlINDI",
+      "name": "uf_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_p": {
+      "__class__": "LogTocElement",
+      "ident": 264,
+      "group": "ctrlINDI",
+      "name": "Omega_f_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_q": {
+      "__class__": "LogTocElement",
+      "ident": 265,
+      "group": "ctrlINDI",
+      "name": "Omega_f_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "Omega_f_r": {
+      "__class__": "LogTocElement",
+      "ident": 266,
+      "group": "ctrlINDI",
+      "name": "Omega_f_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_p": {
+      "__class__": "LogTocElement",
+      "ident": 267,
+      "group": "ctrlINDI",
+      "name": "n_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_q": {
+      "__class__": "LogTocElement",
+      "ident": 268,
+      "group": "ctrlINDI",
+      "name": "n_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "n_r": {
+      "__class__": "LogTocElement",
+      "ident": 269,
+      "group": "ctrlINDI",
+      "name": "n_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "motor": {
+    "m1": {
+      "__class__": "LogTocElement",
+      "ident": 270,
+      "group": "motor",
+      "name": "m1",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m2": {
+      "__class__": "LogTocElement",
+      "ident": 271,
+      "group": "motor",
+      "name": "m2",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m3": {
+      "__class__": "LogTocElement",
+      "ident": 272,
+      "group": "motor",
+      "name": "m3",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    },
+    "m4": {
+      "__class__": "LogTocElement",
+      "ident": 273,
+      "group": "motor",
+      "name": "m4",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "colAv": {
+    "latency": {
+      "__class__": "LogTocElement",
+      "ident": 274,
+      "group": "colAv",
+      "name": "latency",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0
+    }
+  },
+  "health": {
+    "motorVarXM1": {
+      "__class__": "LogTocElement",
+      "ident": 275,
+      "group": "health",
+      "name": "motorVarXM1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM1": {
+      "__class__": "LogTocElement",
+      "ident": 276,
+      "group": "health",
+      "name": "motorVarYM1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM2": {
+      "__class__": "LogTocElement",
+      "ident": 277,
+      "group": "health",
+      "name": "motorVarXM2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM2": {
+      "__class__": "LogTocElement",
+      "ident": 278,
+      "group": "health",
+      "name": "motorVarYM2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM3": {
+      "__class__": "LogTocElement",
+      "ident": 279,
+      "group": "health",
+      "name": "motorVarXM3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM3": {
+      "__class__": "LogTocElement",
+      "ident": 280,
+      "group": "health",
+      "name": "motorVarYM3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarXM4": {
+      "__class__": "LogTocElement",
+      "ident": 281,
+      "group": "health",
+      "name": "motorVarXM4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorVarYM4": {
+      "__class__": "LogTocElement",
+      "ident": 282,
+      "group": "health",
+      "name": "motorVarYM4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "motorPass": {
+      "__class__": "LogTocElement",
+      "ident": 283,
+      "group": "health",
+      "name": "motorPass",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "batterySag": {
+      "__class__": "LogTocElement",
+      "ident": 284,
+      "group": "health",
+      "name": "batterySag",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "batteryPass": {
+      "__class__": "LogTocElement",
+      "ident": 285,
+      "group": "health",
+      "name": "batteryPass",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "motorTestCount": {
+      "__class__": "LogTocElement",
+      "ident": 286,
+      "group": "health",
+      "name": "motorTestCount",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "kalman": {
+    "inFlight": {
+      "__class__": "LogTocElement",
+      "ident": 287,
+      "group": "kalman",
+      "name": "inFlight",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "stateX": {
+      "__class__": "LogTocElement",
+      "ident": 288,
+      "group": "kalman",
+      "name": "stateX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateY": {
+      "__class__": "LogTocElement",
+      "ident": 289,
+      "group": "kalman",
+      "name": "stateY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateZ": {
+      "__class__": "LogTocElement",
+      "ident": 290,
+      "group": "kalman",
+      "name": "stateZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePX": {
+      "__class__": "LogTocElement",
+      "ident": 291,
+      "group": "kalman",
+      "name": "statePX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePY": {
+      "__class__": "LogTocElement",
+      "ident": 292,
+      "group": "kalman",
+      "name": "statePY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "statePZ": {
+      "__class__": "LogTocElement",
+      "ident": 293,
+      "group": "kalman",
+      "name": "statePZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD0": {
+      "__class__": "LogTocElement",
+      "ident": 294,
+      "group": "kalman",
+      "name": "stateD0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD1": {
+      "__class__": "LogTocElement",
+      "ident": 295,
+      "group": "kalman",
+      "name": "stateD1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stateD2": {
+      "__class__": "LogTocElement",
+      "ident": 296,
+      "group": "kalman",
+      "name": "stateD2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varX": {
+      "__class__": "LogTocElement",
+      "ident": 297,
+      "group": "kalman",
+      "name": "varX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varY": {
+      "__class__": "LogTocElement",
+      "ident": 298,
+      "group": "kalman",
+      "name": "varY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varZ": {
+      "__class__": "LogTocElement",
+      "ident": 299,
+      "group": "kalman",
+      "name": "varZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPX": {
+      "__class__": "LogTocElement",
+      "ident": 300,
+      "group": "kalman",
+      "name": "varPX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPY": {
+      "__class__": "LogTocElement",
+      "ident": 301,
+      "group": "kalman",
+      "name": "varPY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varPZ": {
+      "__class__": "LogTocElement",
+      "ident": 302,
+      "group": "kalman",
+      "name": "varPZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD0": {
+      "__class__": "LogTocElement",
+      "ident": 303,
+      "group": "kalman",
+      "name": "varD0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD1": {
+      "__class__": "LogTocElement",
+      "ident": 304,
+      "group": "kalman",
+      "name": "varD1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "varD2": {
+      "__class__": "LogTocElement",
+      "ident": 305,
+      "group": "kalman",
+      "name": "varD2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q0": {
+      "__class__": "LogTocElement",
+      "ident": 306,
+      "group": "kalman",
+      "name": "q0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q1": {
+      "__class__": "LogTocElement",
+      "ident": 307,
+      "group": "kalman",
+      "name": "q1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q2": {
+      "__class__": "LogTocElement",
+      "ident": 308,
+      "group": "kalman",
+      "name": "q2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "q3": {
+      "__class__": "LogTocElement",
+      "ident": 309,
+      "group": "kalman",
+      "name": "q3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtUpdate": {
+      "__class__": "LogTocElement",
+      "ident": 310,
+      "group": "kalman",
+      "name": "rtUpdate",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtPred": {
+      "__class__": "LogTocElement",
+      "ident": 311,
+      "group": "kalman",
+      "name": "rtPred",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rtFinal": {
+      "__class__": "LogTocElement",
+      "ident": 312,
+      "group": "kalman",
+      "name": "rtFinal",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "outlierf": {
+    "lhWin": {
+      "__class__": "LogTocElement",
+      "ident": 313,
+      "group": "outlierf",
+      "name": "lhWin",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket0": {
+      "__class__": "LogTocElement",
+      "ident": 394,
+      "group": "outlierf",
+      "name": "bucket0",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket1": {
+      "__class__": "LogTocElement",
+      "ident": 395,
+      "group": "outlierf",
+      "name": "bucket1",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket2": {
+      "__class__": "LogTocElement",
+      "ident": 396,
+      "group": "outlierf",
+      "name": "bucket2",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket3": {
+      "__class__": "LogTocElement",
+      "ident": 397,
+      "group": "outlierf",
+      "name": "bucket3",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "bucket4": {
+      "__class__": "LogTocElement",
+      "ident": 398,
+      "group": "outlierf",
+      "name": "bucket4",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "accLev": {
+      "__class__": "LogTocElement",
+      "ident": 399,
+      "group": "outlierf",
+      "name": "accLev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "errD": {
+      "__class__": "LogTocElement",
+      "ident": 400,
+      "group": "outlierf",
+      "name": "errD",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "kalman_pred": {
+    "predNX": {
+      "__class__": "LogTocElement",
+      "ident": 314,
+      "group": "kalman_pred",
+      "name": "predNX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "predNY": {
+      "__class__": "LogTocElement",
+      "ident": 315,
+      "group": "kalman_pred",
+      "name": "predNY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "measNX": {
+      "__class__": "LogTocElement",
+      "ident": 316,
+      "group": "kalman_pred",
+      "name": "measNX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "measNY": {
+      "__class__": "LogTocElement",
+      "ident": 317,
+      "group": "kalman_pred",
+      "name": "measNY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ring": {
+    "fadeTime": {
+      "__class__": "LogTocElement",
+      "ident": 318,
+      "group": "ring",
+      "name": "fadeTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "gps": {
+    "lat": {
+      "__class__": "LogTocElement",
+      "ident": 319,
+      "group": "gps",
+      "name": "lat",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "lon": {
+      "__class__": "LogTocElement",
+      "ident": 320,
+      "group": "gps",
+      "name": "lon",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "hMSL": {
+      "__class__": "LogTocElement",
+      "ident": 321,
+      "group": "gps",
+      "name": "hMSL",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "hAcc": {
+      "__class__": "LogTocElement",
+      "ident": 322,
+      "group": "gps",
+      "name": "hAcc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "nsat": {
+      "__class__": "LogTocElement",
+      "ident": 323,
+      "group": "gps",
+      "name": "nsat",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    },
+    "fix": {
+      "__class__": "LogTocElement",
+      "ident": 324,
+      "group": "gps",
+      "name": "fix",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0
+    }
+  },
+  "usd": {
+    "spiWrBps": {
+      "__class__": "LogTocElement",
+      "ident": 325,
+      "group": "usd",
+      "name": "spiWrBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "spiReBps": {
+      "__class__": "LogTocElement",
+      "ident": 326,
+      "group": "usd",
+      "name": "spiReBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "fatWrBps": {
+      "__class__": "LogTocElement",
+      "ident": 327,
+      "group": "usd",
+      "name": "fatWrBps",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "loco": {
+    "mode": {
+      "__class__": "LogTocElement",
+      "ident": 328,
+      "group": "loco",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "spiWr": {
+      "__class__": "LogTocElement",
+      "ident": 329,
+      "group": "loco",
+      "name": "spiWr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "spiRe": {
+      "__class__": "LogTocElement",
+      "ident": 330,
+      "group": "loco",
+      "name": "spiRe",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "ranging": {
+    "state": {
+      "__class__": "LogTocElement",
+      "ident": 331,
+      "group": "ranging",
+      "name": "state",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "distance0": {
+      "__class__": "LogTocElement",
+      "ident": 332,
+      "group": "ranging",
+      "name": "distance0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance1": {
+      "__class__": "LogTocElement",
+      "ident": 333,
+      "group": "ranging",
+      "name": "distance1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance2": {
+      "__class__": "LogTocElement",
+      "ident": 334,
+      "group": "ranging",
+      "name": "distance2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance3": {
+      "__class__": "LogTocElement",
+      "ident": 335,
+      "group": "ranging",
+      "name": "distance3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance4": {
+      "__class__": "LogTocElement",
+      "ident": 336,
+      "group": "ranging",
+      "name": "distance4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance5": {
+      "__class__": "LogTocElement",
+      "ident": 337,
+      "group": "ranging",
+      "name": "distance5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance6": {
+      "__class__": "LogTocElement",
+      "ident": 338,
+      "group": "ranging",
+      "name": "distance6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "distance7": {
+      "__class__": "LogTocElement",
+      "ident": 339,
+      "group": "ranging",
+      "name": "distance7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure0": {
+      "__class__": "LogTocElement",
+      "ident": 340,
+      "group": "ranging",
+      "name": "pressure0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure1": {
+      "__class__": "LogTocElement",
+      "ident": 341,
+      "group": "ranging",
+      "name": "pressure1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure2": {
+      "__class__": "LogTocElement",
+      "ident": 342,
+      "group": "ranging",
+      "name": "pressure2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure3": {
+      "__class__": "LogTocElement",
+      "ident": 343,
+      "group": "ranging",
+      "name": "pressure3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure4": {
+      "__class__": "LogTocElement",
+      "ident": 344,
+      "group": "ranging",
+      "name": "pressure4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure5": {
+      "__class__": "LogTocElement",
+      "ident": 345,
+      "group": "ranging",
+      "name": "pressure5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure6": {
+      "__class__": "LogTocElement",
+      "ident": 346,
+      "group": "ranging",
+      "name": "pressure6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "pressure7": {
+      "__class__": "LogTocElement",
+      "ident": 347,
+      "group": "ranging",
+      "name": "pressure7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "twr": {
+    "rangingSuccessRate0": {
+      "__class__": "LogTocElement",
+      "ident": 348,
+      "group": "twr",
+      "name": "rangingSuccessRate0",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec0": {
+      "__class__": "LogTocElement",
+      "ident": 349,
+      "group": "twr",
+      "name": "rangingPerSec0",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate1": {
+      "__class__": "LogTocElement",
+      "ident": 350,
+      "group": "twr",
+      "name": "rangingSuccessRate1",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec1": {
+      "__class__": "LogTocElement",
+      "ident": 351,
+      "group": "twr",
+      "name": "rangingPerSec1",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate2": {
+      "__class__": "LogTocElement",
+      "ident": 352,
+      "group": "twr",
+      "name": "rangingSuccessRate2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec2": {
+      "__class__": "LogTocElement",
+      "ident": 353,
+      "group": "twr",
+      "name": "rangingPerSec2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate3": {
+      "__class__": "LogTocElement",
+      "ident": 354,
+      "group": "twr",
+      "name": "rangingSuccessRate3",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec3": {
+      "__class__": "LogTocElement",
+      "ident": 355,
+      "group": "twr",
+      "name": "rangingPerSec3",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate4": {
+      "__class__": "LogTocElement",
+      "ident": 356,
+      "group": "twr",
+      "name": "rangingSuccessRate4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec4": {
+      "__class__": "LogTocElement",
+      "ident": 357,
+      "group": "twr",
+      "name": "rangingPerSec4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingSuccessRate5": {
+      "__class__": "LogTocElement",
+      "ident": 358,
+      "group": "twr",
+      "name": "rangingSuccessRate5",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rangingPerSec5": {
+      "__class__": "LogTocElement",
+      "ident": 359,
+      "group": "twr",
+      "name": "rangingPerSec5",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "tdoa2": {
+    "d7-0": {
+      "__class__": "LogTocElement",
+      "ident": 360,
+      "group": "tdoa2",
+      "name": "d7-0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d0-1": {
+      "__class__": "LogTocElement",
+      "ident": 361,
+      "group": "tdoa2",
+      "name": "d0-1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d1-2": {
+      "__class__": "LogTocElement",
+      "ident": 362,
+      "group": "tdoa2",
+      "name": "d1-2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d2-3": {
+      "__class__": "LogTocElement",
+      "ident": 363,
+      "group": "tdoa2",
+      "name": "d2-3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d3-4": {
+      "__class__": "LogTocElement",
+      "ident": 364,
+      "group": "tdoa2",
+      "name": "d3-4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d4-5": {
+      "__class__": "LogTocElement",
+      "ident": 365,
+      "group": "tdoa2",
+      "name": "d4-5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d5-6": {
+      "__class__": "LogTocElement",
+      "ident": 366,
+      "group": "tdoa2",
+      "name": "d5-6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "d6-7": {
+      "__class__": "LogTocElement",
+      "ident": 367,
+      "group": "tdoa2",
+      "name": "d6-7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc0": {
+      "__class__": "LogTocElement",
+      "ident": 368,
+      "group": "tdoa2",
+      "name": "cc0",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc1": {
+      "__class__": "LogTocElement",
+      "ident": 369,
+      "group": "tdoa2",
+      "name": "cc1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc2": {
+      "__class__": "LogTocElement",
+      "ident": 370,
+      "group": "tdoa2",
+      "name": "cc2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc3": {
+      "__class__": "LogTocElement",
+      "ident": 371,
+      "group": "tdoa2",
+      "name": "cc3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc4": {
+      "__class__": "LogTocElement",
+      "ident": 372,
+      "group": "tdoa2",
+      "name": "cc4",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc5": {
+      "__class__": "LogTocElement",
+      "ident": 373,
+      "group": "tdoa2",
+      "name": "cc5",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc6": {
+      "__class__": "LogTocElement",
+      "ident": 374,
+      "group": "tdoa2",
+      "name": "cc6",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc7": {
+      "__class__": "LogTocElement",
+      "ident": 375,
+      "group": "tdoa2",
+      "name": "cc7",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "dist7-0": {
+      "__class__": "LogTocElement",
+      "ident": 376,
+      "group": "tdoa2",
+      "name": "dist7-0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist0-1": {
+      "__class__": "LogTocElement",
+      "ident": 377,
+      "group": "tdoa2",
+      "name": "dist0-1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist1-2": {
+      "__class__": "LogTocElement",
+      "ident": 378,
+      "group": "tdoa2",
+      "name": "dist1-2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist2-3": {
+      "__class__": "LogTocElement",
+      "ident": 379,
+      "group": "tdoa2",
+      "name": "dist2-3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist3-4": {
+      "__class__": "LogTocElement",
+      "ident": 380,
+      "group": "tdoa2",
+      "name": "dist3-4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist4-5": {
+      "__class__": "LogTocElement",
+      "ident": 381,
+      "group": "tdoa2",
+      "name": "dist4-5",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist5-6": {
+      "__class__": "LogTocElement",
+      "ident": 382,
+      "group": "tdoa2",
+      "name": "dist5-6",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "dist6-7": {
+      "__class__": "LogTocElement",
+      "ident": 383,
+      "group": "tdoa2",
+      "name": "dist6-7",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "tdoaEngine": {
+    "stRx": {
+      "__class__": "LogTocElement",
+      "ident": 384,
+      "group": "tdoaEngine",
+      "name": "stRx",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stEst": {
+      "__class__": "LogTocElement",
+      "ident": 385,
+      "group": "tdoaEngine",
+      "name": "stEst",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stTime": {
+      "__class__": "LogTocElement",
+      "ident": 386,
+      "group": "tdoaEngine",
+      "name": "stTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stFound": {
+      "__class__": "LogTocElement",
+      "ident": 387,
+      "group": "tdoaEngine",
+      "name": "stFound",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stCc": {
+      "__class__": "LogTocElement",
+      "ident": 388,
+      "group": "tdoaEngine",
+      "name": "stCc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stHit": {
+      "__class__": "LogTocElement",
+      "ident": 389,
+      "group": "tdoaEngine",
+      "name": "stHit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "stMiss": {
+      "__class__": "LogTocElement",
+      "ident": 390,
+      "group": "tdoaEngine",
+      "name": "stMiss",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cc": {
+      "__class__": "LogTocElement",
+      "ident": 391,
+      "group": "tdoaEngine",
+      "name": "cc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "tof": {
+      "__class__": "LogTocElement",
+      "ident": 392,
+      "group": "tdoaEngine",
+      "name": "tof",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "tdoa": {
+      "__class__": "LogTocElement",
+      "ident": 393,
+      "group": "tdoaEngine",
+      "name": "tdoa",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "motion": {
+    "motion": {
+      "__class__": "LogTocElement",
+      "ident": 401,
+      "group": "motion",
+      "name": "motion",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "deltaX": {
+      "__class__": "LogTocElement",
+      "ident": 402,
+      "group": "motion",
+      "name": "deltaX",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "deltaY": {
+      "__class__": "LogTocElement",
+      "ident": 403,
+      "group": "motion",
+      "name": "deltaY",
+      "ctype": "int16_t",
+      "pytype": "<h",
+      "access": 0
+    },
+    "shutter": {
+      "__class__": "LogTocElement",
+      "ident": 404,
+      "group": "motion",
+      "name": "shutter",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "maxRaw": {
+      "__class__": "LogTocElement",
+      "ident": 405,
+      "group": "motion",
+      "name": "maxRaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "minRaw": {
+      "__class__": "LogTocElement",
+      "ident": 406,
+      "group": "motion",
+      "name": "minRaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "Rawsum": {
+      "__class__": "LogTocElement",
+      "ident": 407,
+      "group": "motion",
+      "name": "Rawsum",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "outlierCount": {
+      "__class__": "LogTocElement",
+      "ident": 408,
+      "group": "motion",
+      "name": "outlierCount",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "squal": {
+      "__class__": "LogTocElement",
+      "ident": 409,
+      "group": "motion",
+      "name": "squal",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "std": {
+      "__class__": "LogTocElement",
+      "ident": 410,
+      "group": "motion",
+      "name": "std",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    }
+  },
+  "oa": {
+    "front": {
+      "__class__": "LogTocElement",
+      "ident": 411,
+      "group": "oa",
+      "name": "front",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "back": {
+      "__class__": "LogTocElement",
+      "ident": 412,
+      "group": "oa",
+      "name": "back",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "up": {
+      "__class__": "LogTocElement",
+      "ident": 413,
+      "group": "oa",
+      "name": "up",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "left": {
+      "__class__": "LogTocElement",
+      "ident": 414,
+      "group": "oa",
+      "name": "left",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "right": {
+      "__class__": "LogTocElement",
+      "ident": 415,
+      "group": "oa",
+      "name": "right",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  },
+  "activeMarker": {
+    "btSns": {
+      "__class__": "LogTocElement",
+      "ident": 416,
+      "group": "activeMarker",
+      "name": "btSns",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "i2cOk": {
+      "__class__": "LogTocElement",
+      "ident": 417,
+      "group": "activeMarker",
+      "name": "i2cOk",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "aideck": {
+    "receivebyte": {
+      "__class__": "LogTocElement",
+      "ident": 418,
+      "group": "aideck",
+      "name": "receivebyte",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    }
+  },
+  "lighthouse": {
+    "validAngles": {
+      "__class__": "LogTocElement",
+      "ident": 419,
+      "group": "lighthouse",
+      "name": "validAngles",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "rawAngle0x": {
+      "__class__": "LogTocElement",
+      "ident": 420,
+      "group": "lighthouse",
+      "name": "rawAngle0x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0y": {
+      "__class__": "LogTocElement",
+      "ident": 421,
+      "group": "lighthouse",
+      "name": "rawAngle0y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1x": {
+      "__class__": "LogTocElement",
+      "ident": 422,
+      "group": "lighthouse",
+      "name": "rawAngle1x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1y": {
+      "__class__": "LogTocElement",
+      "ident": 423,
+      "group": "lighthouse",
+      "name": "rawAngle1y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x": {
+      "__class__": "LogTocElement",
+      "ident": 424,
+      "group": "lighthouse",
+      "name": "angle0x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y": {
+      "__class__": "LogTocElement",
+      "ident": 425,
+      "group": "lighthouse",
+      "name": "angle0y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x": {
+      "__class__": "LogTocElement",
+      "ident": 426,
+      "group": "lighthouse",
+      "name": "angle1x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y": {
+      "__class__": "LogTocElement",
+      "ident": 427,
+      "group": "lighthouse",
+      "name": "angle1y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_1": {
+      "__class__": "LogTocElement",
+      "ident": 428,
+      "group": "lighthouse",
+      "name": "angle0x_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_1": {
+      "__class__": "LogTocElement",
+      "ident": 429,
+      "group": "lighthouse",
+      "name": "angle0y_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_1": {
+      "__class__": "LogTocElement",
+      "ident": 430,
+      "group": "lighthouse",
+      "name": "angle1x_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_1": {
+      "__class__": "LogTocElement",
+      "ident": 431,
+      "group": "lighthouse",
+      "name": "angle1y_1",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_2": {
+      "__class__": "LogTocElement",
+      "ident": 432,
+      "group": "lighthouse",
+      "name": "angle0x_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_2": {
+      "__class__": "LogTocElement",
+      "ident": 433,
+      "group": "lighthouse",
+      "name": "angle0y_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_2": {
+      "__class__": "LogTocElement",
+      "ident": 434,
+      "group": "lighthouse",
+      "name": "angle1x_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_2": {
+      "__class__": "LogTocElement",
+      "ident": 435,
+      "group": "lighthouse",
+      "name": "angle1y_2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_3": {
+      "__class__": "LogTocElement",
+      "ident": 436,
+      "group": "lighthouse",
+      "name": "angle0x_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_3": {
+      "__class__": "LogTocElement",
+      "ident": 437,
+      "group": "lighthouse",
+      "name": "angle0y_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_3": {
+      "__class__": "LogTocElement",
+      "ident": 438,
+      "group": "lighthouse",
+      "name": "angle1x_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_3": {
+      "__class__": "LogTocElement",
+      "ident": 439,
+      "group": "lighthouse",
+      "name": "angle1y_3",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0xlh2": {
+      "__class__": "LogTocElement",
+      "ident": 440,
+      "group": "lighthouse",
+      "name": "rawAngle0xlh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle0ylh2": {
+      "__class__": "LogTocElement",
+      "ident": 441,
+      "group": "lighthouse",
+      "name": "rawAngle0ylh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1xlh2": {
+      "__class__": "LogTocElement",
+      "ident": 442,
+      "group": "lighthouse",
+      "name": "rawAngle1xlh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "rawAngle1ylh2": {
+      "__class__": "LogTocElement",
+      "ident": 443,
+      "group": "lighthouse",
+      "name": "rawAngle1ylh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0x_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 444,
+      "group": "lighthouse",
+      "name": "angle0x_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle0y_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 445,
+      "group": "lighthouse",
+      "name": "angle0y_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1x_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 446,
+      "group": "lighthouse",
+      "name": "angle1x_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "angle1y_0lh2": {
+      "__class__": "LogTocElement",
+      "ident": 447,
+      "group": "lighthouse",
+      "name": "angle1y_0lh2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "serRt": {
+      "__class__": "LogTocElement",
+      "ident": 448,
+      "group": "lighthouse",
+      "name": "serRt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "frmRt": {
+      "__class__": "LogTocElement",
+      "ident": 449,
+      "group": "lighthouse",
+      "name": "frmRt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "cycleRt": {
+      "__class__": "LogTocElement",
+      "ident": 450,
+      "group": "lighthouse",
+      "name": "cycleRt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bs0Rt": {
+      "__class__": "LogTocElement",
+      "ident": 451,
+      "group": "lighthouse",
+      "name": "bs0Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bs1Rt": {
+      "__class__": "LogTocElement",
+      "ident": 452,
+      "group": "lighthouse",
+      "name": "bs1Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "width0": {
+      "__class__": "LogTocElement",
+      "ident": 453,
+      "group": "lighthouse",
+      "name": "width0",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width1": {
+      "__class__": "LogTocElement",
+      "ident": 454,
+      "group": "lighthouse",
+      "name": "width1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width2": {
+      "__class__": "LogTocElement",
+      "ident": 455,
+      "group": "lighthouse",
+      "name": "width2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "width3": {
+      "__class__": "LogTocElement",
+      "ident": 456,
+      "group": "lighthouse",
+      "name": "width3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "comSync": {
+      "__class__": "LogTocElement",
+      "ident": 457,
+      "group": "lighthouse",
+      "name": "comSync",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "bsReceive": {
+      "__class__": "LogTocElement",
+      "ident": 458,
+      "group": "lighthouse",
+      "name": "bsReceive",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsActive": {
+      "__class__": "LogTocElement",
+      "ident": 459,
+      "group": "lighthouse",
+      "name": "bsActive",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalUd": {
+      "__class__": "LogTocElement",
+      "ident": 460,
+      "group": "lighthouse",
+      "name": "bsCalUd",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalCon": {
+      "__class__": "LogTocElement",
+      "ident": 461,
+      "group": "lighthouse",
+      "name": "bsCalCon",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "status": {
+      "__class__": "LogTocElement",
+      "ident": 462,
+      "group": "lighthouse",
+      "name": "status",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0
+    },
+    "posRt": {
+      "__class__": "LogTocElement",
+      "ident": 463,
+      "group": "lighthouse",
+      "name": "posRt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estBs0Rt": {
+      "__class__": "LogTocElement",
+      "ident": 464,
+      "group": "lighthouse",
+      "name": "estBs0Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "estBs1Rt": {
+      "__class__": "LogTocElement",
+      "ident": 465,
+      "group": "lighthouse",
+      "name": "estBs1Rt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "x": {
+      "__class__": "LogTocElement",
+      "ident": 466,
+      "group": "lighthouse",
+      "name": "x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "y": {
+      "__class__": "LogTocElement",
+      "ident": 467,
+      "group": "lighthouse",
+      "name": "y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "z": {
+      "__class__": "LogTocElement",
+      "ident": 468,
+      "group": "lighthouse",
+      "name": "z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "delta": {
+      "__class__": "LogTocElement",
+      "ident": 469,
+      "group": "lighthouse",
+      "name": "delta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0
+    },
+    "bsGeoVal": {
+      "__class__": "LogTocElement",
+      "ident": 470,
+      "group": "lighthouse",
+      "name": "bsGeoVal",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    },
+    "bsCalVal": {
+      "__class__": "LogTocElement",
+      "ident": 471,
+      "group": "lighthouse",
+      "name": "bsCalVal",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0
+    }
+  }
+}
\ No newline at end of file
diff --git a/crazyflie_demos/cache/E60D1F34.json b/crazyflie_demos/cache/E60D1F34.json
new file mode 100644
index 0000000000000000000000000000000000000000..c8cf8e023dd087ad54616b244342301278689bfb
--- /dev/null
+++ b/crazyflie_demos/cache/E60D1F34.json
@@ -0,0 +1,2820 @@
+{
+  "activeMarker": {
+    "front": {
+      "__class__": "ParamTocElement",
+      "ident": 0,
+      "group": "activeMarker",
+      "name": "front",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "back": {
+      "__class__": "ParamTocElement",
+      "ident": 1,
+      "group": "activeMarker",
+      "name": "back",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "left": {
+      "__class__": "ParamTocElement",
+      "ident": 2,
+      "group": "activeMarker",
+      "name": "left",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "right": {
+      "__class__": "ParamTocElement",
+      "ident": 3,
+      "group": "activeMarker",
+      "name": "right",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "mode": {
+      "__class__": "ParamTocElement",
+      "ident": 4,
+      "group": "activeMarker",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "poll": {
+      "__class__": "ParamTocElement",
+      "ident": 5,
+      "group": "activeMarker",
+      "name": "poll",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "deck": {
+    "bcActiveMarker": {
+      "__class__": "ParamTocElement",
+      "ident": 6,
+      "group": "deck",
+      "name": "bcActiveMarker",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcAI": {
+      "__class__": "ParamTocElement",
+      "ident": 7,
+      "group": "deck",
+      "name": "bcAI",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcBuzzer": {
+      "__class__": "ParamTocElement",
+      "ident": 8,
+      "group": "deck",
+      "name": "bcBuzzer",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcFlow": {
+      "__class__": "ParamTocElement",
+      "ident": 9,
+      "group": "deck",
+      "name": "bcFlow",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcFlow2": {
+      "__class__": "ParamTocElement",
+      "ident": 10,
+      "group": "deck",
+      "name": "bcFlow2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcLedRing": {
+      "__class__": "ParamTocElement",
+      "ident": 11,
+      "group": "deck",
+      "name": "bcLedRing",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcLighthouse4": {
+      "__class__": "ParamTocElement",
+      "ident": 12,
+      "group": "deck",
+      "name": "bcLighthouse4",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcDWM1000": {
+      "__class__": "ParamTocElement",
+      "ident": 13,
+      "group": "deck",
+      "name": "bcDWM1000",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcMultiranger": {
+      "__class__": "ParamTocElement",
+      "ident": 14,
+      "group": "deck",
+      "name": "bcMultiranger",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcOA": {
+      "__class__": "ParamTocElement",
+      "ident": 15,
+      "group": "deck",
+      "name": "bcOA",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcUSD": {
+      "__class__": "ParamTocElement",
+      "ident": 16,
+      "group": "deck",
+      "name": "bcUSD",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcZRanger": {
+      "__class__": "ParamTocElement",
+      "ident": 17,
+      "group": "deck",
+      "name": "bcZRanger",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "bcZRanger2": {
+      "__class__": "ParamTocElement",
+      "ident": 18,
+      "group": "deck",
+      "name": "bcZRanger2",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "motion": {
+    "disable": {
+      "__class__": "ParamTocElement",
+      "ident": 19,
+      "group": "motion",
+      "name": "disable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "adaptive": {
+      "__class__": "ParamTocElement",
+      "ident": 20,
+      "group": "motion",
+      "name": "adaptive",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "flowStdFixed": {
+      "__class__": "ParamTocElement",
+      "ident": 21,
+      "group": "motion",
+      "name": "flowStdFixed",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ring": {
+    "effect": {
+      "__class__": "ParamTocElement",
+      "ident": 22,
+      "group": "ring",
+      "name": "effect",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "neffect": {
+      "__class__": "ParamTocElement",
+      "ident": 23,
+      "group": "ring",
+      "name": "neffect",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "solidRed": {
+      "__class__": "ParamTocElement",
+      "ident": 24,
+      "group": "ring",
+      "name": "solidRed",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "solidGreen": {
+      "__class__": "ParamTocElement",
+      "ident": 25,
+      "group": "ring",
+      "name": "solidGreen",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "solidBlue": {
+      "__class__": "ParamTocElement",
+      "ident": 26,
+      "group": "ring",
+      "name": "solidBlue",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "headlightEnable": {
+      "__class__": "ParamTocElement",
+      "ident": 27,
+      "group": "ring",
+      "name": "headlightEnable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "emptyCharge": {
+      "__class__": "ParamTocElement",
+      "ident": 28,
+      "group": "ring",
+      "name": "emptyCharge",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "fullCharge": {
+      "__class__": "ParamTocElement",
+      "ident": 29,
+      "group": "ring",
+      "name": "fullCharge",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "fadeColor": {
+      "__class__": "ParamTocElement",
+      "ident": 30,
+      "group": "ring",
+      "name": "fadeColor",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0,
+      "extended": false
+    },
+    "fadeTime": {
+      "__class__": "ParamTocElement",
+      "ident": 31,
+      "group": "ring",
+      "name": "fadeTime",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "system": {
+    "highlight": {
+      "__class__": "ParamTocElement",
+      "ident": 32,
+      "group": "system",
+      "name": "highlight",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "storageStats": {
+      "__class__": "ParamTocElement",
+      "ident": 33,
+      "group": "system",
+      "name": "storageStats",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "taskDump": {
+      "__class__": "ParamTocElement",
+      "ident": 34,
+      "group": "system",
+      "name": "taskDump",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "selftestPassed": {
+      "__class__": "ParamTocElement",
+      "ident": 35,
+      "group": "system",
+      "name": "selftestPassed",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 1,
+      "extended": false
+    },
+    "forceArm": {
+      "__class__": "ParamTocElement",
+      "ident": 36,
+      "group": "system",
+      "name": "forceArm",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0,
+      "extended": true
+    },
+    "assertInfo": {
+      "__class__": "ParamTocElement",
+      "ident": 37,
+      "group": "system",
+      "name": "assertInfo",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "loco": {
+    "mode": {
+      "__class__": "ParamTocElement",
+      "ident": 38,
+      "group": "loco",
+      "name": "mode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "tdoa2": {
+    "stddev": {
+      "__class__": "ParamTocElement",
+      "ident": 39,
+      "group": "tdoa2",
+      "name": "stddev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "tdoa3": {
+    "stddev": {
+      "__class__": "ParamTocElement",
+      "ident": 40,
+      "group": "tdoa3",
+      "name": "stddev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "multiranger": {
+    "filterMask": {
+      "__class__": "ParamTocElement",
+      "ident": 41,
+      "group": "multiranger",
+      "name": "filterMask",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "usd": {
+    "canLog": {
+      "__class__": "ParamTocElement",
+      "ident": 42,
+      "group": "usd",
+      "name": "canLog",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "logging": {
+      "__class__": "ParamTocElement",
+      "ident": 43,
+      "group": "usd",
+      "name": "logging",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "led": {
+    "bitmask": {
+      "__class__": "ParamTocElement",
+      "ident": 44,
+      "group": "led",
+      "name": "bitmask",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "motorPowerSet": {
+    "enable": {
+      "__class__": "ParamTocElement",
+      "ident": 45,
+      "group": "motorPowerSet",
+      "name": "enable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "m1": {
+      "__class__": "ParamTocElement",
+      "ident": 46,
+      "group": "motorPowerSet",
+      "name": "m1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m2": {
+      "__class__": "ParamTocElement",
+      "ident": 47,
+      "group": "motorPowerSet",
+      "name": "m2",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m3": {
+      "__class__": "ParamTocElement",
+      "ident": 48,
+      "group": "motorPowerSet",
+      "name": "m3",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    },
+    "m4": {
+      "__class__": "ParamTocElement",
+      "ident": 49,
+      "group": "motorPowerSet",
+      "name": "m4",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "pm": {
+    "lowVoltage": {
+      "__class__": "ParamTocElement",
+      "ident": 50,
+      "group": "pm",
+      "name": "lowVoltage",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "criticalLowVoltage": {
+      "__class__": "ParamTocElement",
+      "ident": 51,
+      "group": "pm",
+      "name": "criticalLowVoltage",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "imu_sensors": {
+    "BMP388": {
+      "__class__": "ParamTocElement",
+      "ident": 52,
+      "group": "imu_sensors",
+      "name": "BMP388",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "imuPhi": {
+      "__class__": "ParamTocElement",
+      "ident": 53,
+      "group": "imu_sensors",
+      "name": "imuPhi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuTheta": {
+      "__class__": "ParamTocElement",
+      "ident": 54,
+      "group": "imu_sensors",
+      "name": "imuTheta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuPsi": {
+      "__class__": "ParamTocElement",
+      "ident": 55,
+      "group": "imu_sensors",
+      "name": "imuPsi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "AK8963": {
+      "__class__": "ParamTocElement",
+      "ident": 56,
+      "group": "imu_sensors",
+      "name": "AK8963",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "LPS25H": {
+      "__class__": "ParamTocElement",
+      "ident": 57,
+      "group": "imu_sensors",
+      "name": "LPS25H",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "imu_tests": {
+    "MPU6500": {
+      "__class__": "ParamTocElement",
+      "ident": 58,
+      "group": "imu_tests",
+      "name": "MPU6500",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "AK8963": {
+      "__class__": "ParamTocElement",
+      "ident": 59,
+      "group": "imu_tests",
+      "name": "AK8963",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "LPS25H": {
+      "__class__": "ParamTocElement",
+      "ident": 60,
+      "group": "imu_tests",
+      "name": "LPS25H",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    },
+    "imuPhi": {
+      "__class__": "ParamTocElement",
+      "ident": 61,
+      "group": "imu_tests",
+      "name": "imuPhi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuTheta": {
+      "__class__": "ParamTocElement",
+      "ident": 62,
+      "group": "imu_tests",
+      "name": "imuTheta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "imuPsi": {
+      "__class__": "ParamTocElement",
+      "ident": 63,
+      "group": "imu_tests",
+      "name": "imuPsi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "syslink": {
+    "probe": {
+      "__class__": "ParamTocElement",
+      "ident": 64,
+      "group": "syslink",
+      "name": "probe",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "pid_attitude": {
+    "roll_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 65,
+      "group": "pid_attitude",
+      "name": "roll_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 66,
+      "group": "pid_attitude",
+      "name": "roll_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 67,
+      "group": "pid_attitude",
+      "name": "roll_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 68,
+      "group": "pid_attitude",
+      "name": "roll_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 69,
+      "group": "pid_attitude",
+      "name": "pitch_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 70,
+      "group": "pid_attitude",
+      "name": "pitch_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 71,
+      "group": "pid_attitude",
+      "name": "pitch_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 72,
+      "group": "pid_attitude",
+      "name": "pitch_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 73,
+      "group": "pid_attitude",
+      "name": "yaw_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 74,
+      "group": "pid_attitude",
+      "name": "yaw_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 75,
+      "group": "pid_attitude",
+      "name": "yaw_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 76,
+      "group": "pid_attitude",
+      "name": "yaw_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yawMaxDelta": {
+      "__class__": "ParamTocElement",
+      "ident": 77,
+      "group": "pid_attitude",
+      "name": "yawMaxDelta",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "attFiltEn": {
+      "__class__": "ParamTocElement",
+      "ident": 78,
+      "group": "pid_attitude",
+      "name": "attFiltEn",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0,
+      "extended": true
+    },
+    "attFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 79,
+      "group": "pid_attitude",
+      "name": "attFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "pid_rate": {
+    "roll_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 80,
+      "group": "pid_rate",
+      "name": "roll_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 81,
+      "group": "pid_rate",
+      "name": "roll_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 82,
+      "group": "pid_rate",
+      "name": "roll_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "roll_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 83,
+      "group": "pid_rate",
+      "name": "roll_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 84,
+      "group": "pid_rate",
+      "name": "pitch_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 85,
+      "group": "pid_rate",
+      "name": "pitch_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 86,
+      "group": "pid_rate",
+      "name": "pitch_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pitch_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 87,
+      "group": "pid_rate",
+      "name": "pitch_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kp": {
+      "__class__": "ParamTocElement",
+      "ident": 88,
+      "group": "pid_rate",
+      "name": "yaw_kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_ki": {
+      "__class__": "ParamTocElement",
+      "ident": 89,
+      "group": "pid_rate",
+      "name": "yaw_ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kd": {
+      "__class__": "ParamTocElement",
+      "ident": 90,
+      "group": "pid_rate",
+      "name": "yaw_kd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yaw_kff": {
+      "__class__": "ParamTocElement",
+      "ident": 91,
+      "group": "pid_rate",
+      "name": "yaw_kff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "rateFiltEn": {
+      "__class__": "ParamTocElement",
+      "ident": 92,
+      "group": "pid_rate",
+      "name": "rateFiltEn",
+      "ctype": "int8_t",
+      "pytype": "<b",
+      "access": 0,
+      "extended": true
+    },
+    "omxFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 93,
+      "group": "pid_rate",
+      "name": "omxFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "omyFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 94,
+      "group": "pid_rate",
+      "name": "omyFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "omzFiltCut": {
+      "__class__": "ParamTocElement",
+      "ident": 95,
+      "group": "pid_rate",
+      "name": "omzFiltCut",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "colAv": {
+    "enable": {
+      "__class__": "ParamTocElement",
+      "ident": 96,
+      "group": "colAv",
+      "name": "enable",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidX": {
+      "__class__": "ParamTocElement",
+      "ident": 97,
+      "group": "colAv",
+      "name": "ellipsoidX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidY": {
+      "__class__": "ParamTocElement",
+      "ident": 98,
+      "group": "colAv",
+      "name": "ellipsoidY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ellipsoidZ": {
+      "__class__": "ParamTocElement",
+      "ident": 99,
+      "group": "colAv",
+      "name": "ellipsoidZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinX": {
+      "__class__": "ParamTocElement",
+      "ident": 100,
+      "group": "colAv",
+      "name": "bboxMinX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinY": {
+      "__class__": "ParamTocElement",
+      "ident": 101,
+      "group": "colAv",
+      "name": "bboxMinY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMinZ": {
+      "__class__": "ParamTocElement",
+      "ident": 102,
+      "group": "colAv",
+      "name": "bboxMinZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxX": {
+      "__class__": "ParamTocElement",
+      "ident": 103,
+      "group": "colAv",
+      "name": "bboxMaxX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxY": {
+      "__class__": "ParamTocElement",
+      "ident": 104,
+      "group": "colAv",
+      "name": "bboxMaxY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bboxMaxZ": {
+      "__class__": "ParamTocElement",
+      "ident": 105,
+      "group": "colAv",
+      "name": "bboxMaxZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "horizon": {
+      "__class__": "ParamTocElement",
+      "ident": 106,
+      "group": "colAv",
+      "name": "horizon",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxSpeed": {
+      "__class__": "ParamTocElement",
+      "ident": 107,
+      "group": "colAv",
+      "name": "maxSpeed",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "sidestepThrsh": {
+      "__class__": "ParamTocElement",
+      "ident": 108,
+      "group": "colAv",
+      "name": "sidestepThrsh",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxPeerLocAge": {
+      "__class__": "ParamTocElement",
+      "ident": 109,
+      "group": "colAv",
+      "name": "maxPeerLocAge",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0,
+      "extended": false
+    },
+    "vorTol": {
+      "__class__": "ParamTocElement",
+      "ident": 110,
+      "group": "colAv",
+      "name": "vorTol",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vorIters": {
+      "__class__": "ParamTocElement",
+      "ident": 111,
+      "group": "colAv",
+      "name": "vorIters",
+      "ctype": "int32_t",
+      "pytype": "<i",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "commander": {
+    "enHighLevel": {
+      "__class__": "ParamTocElement",
+      "ident": 112,
+      "group": "commander",
+      "name": "enHighLevel",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ctrlINDI": {
+    "thrust_threshold": {
+      "__class__": "ParamTocElement",
+      "ident": 113,
+      "group": "ctrlINDI",
+      "name": "thrust_threshold",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "bound_ctrl_input": {
+      "__class__": "ParamTocElement",
+      "ident": 114,
+      "group": "ctrlINDI",
+      "name": "bound_ctrl_input",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_p": {
+      "__class__": "ParamTocElement",
+      "ident": 115,
+      "group": "ctrlINDI",
+      "name": "g1_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_q": {
+      "__class__": "ParamTocElement",
+      "ident": 116,
+      "group": "ctrlINDI",
+      "name": "g1_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g1_r": {
+      "__class__": "ParamTocElement",
+      "ident": 117,
+      "group": "ctrlINDI",
+      "name": "g1_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "g2": {
+      "__class__": "ParamTocElement",
+      "ident": 118,
+      "group": "ctrlINDI",
+      "name": "g2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_p": {
+      "__class__": "ParamTocElement",
+      "ident": 119,
+      "group": "ctrlINDI",
+      "name": "ref_err_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_q": {
+      "__class__": "ParamTocElement",
+      "ident": 120,
+      "group": "ctrlINDI",
+      "name": "ref_err_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_err_r": {
+      "__class__": "ParamTocElement",
+      "ident": 121,
+      "group": "ctrlINDI",
+      "name": "ref_err_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_p": {
+      "__class__": "ParamTocElement",
+      "ident": 122,
+      "group": "ctrlINDI",
+      "name": "ref_rate_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_q": {
+      "__class__": "ParamTocElement",
+      "ident": 123,
+      "group": "ctrlINDI",
+      "name": "ref_rate_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "ref_rate_r": {
+      "__class__": "ParamTocElement",
+      "ident": 124,
+      "group": "ctrlINDI",
+      "name": "ref_rate_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_p": {
+      "__class__": "ParamTocElement",
+      "ident": 125,
+      "group": "ctrlINDI",
+      "name": "act_dyn_p",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_q": {
+      "__class__": "ParamTocElement",
+      "ident": 126,
+      "group": "ctrlINDI",
+      "name": "act_dyn_q",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "act_dyn_r": {
+      "__class__": "ParamTocElement",
+      "ident": 127,
+      "group": "ctrlINDI",
+      "name": "act_dyn_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "filt_cutoff": {
+      "__class__": "ParamTocElement",
+      "ident": 128,
+      "group": "ctrlINDI",
+      "name": "filt_cutoff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "filt_cutoff_r": {
+      "__class__": "ParamTocElement",
+      "ident": 129,
+      "group": "ctrlINDI",
+      "name": "filt_cutoff_r",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "outerLoopActive": {
+      "__class__": "ParamTocElement",
+      "ident": 130,
+      "group": "ctrlINDI",
+      "name": "outerLoopActive",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "ctrlMel": {
+    "kp_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 131,
+      "group": "ctrlMel",
+      "name": "kp_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kd_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 132,
+      "group": "ctrlMel",
+      "name": "kd_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 133,
+      "group": "ctrlMel",
+      "name": "ki_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 134,
+      "group": "ctrlMel",
+      "name": "i_range_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kp_z": {
+      "__class__": "ParamTocElement",
+      "ident": 135,
+      "group": "ctrlMel",
+      "name": "kp_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kd_z": {
+      "__class__": "ParamTocElement",
+      "ident": 136,
+      "group": "ctrlMel",
+      "name": "kd_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_z": {
+      "__class__": "ParamTocElement",
+      "ident": 137,
+      "group": "ctrlMel",
+      "name": "ki_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_z": {
+      "__class__": "ParamTocElement",
+      "ident": 138,
+      "group": "ctrlMel",
+      "name": "i_range_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mass": {
+      "__class__": "ParamTocElement",
+      "ident": 139,
+      "group": "ctrlMel",
+      "name": "mass",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "massThrust": {
+      "__class__": "ParamTocElement",
+      "ident": 140,
+      "group": "ctrlMel",
+      "name": "massThrust",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kR_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 141,
+      "group": "ctrlMel",
+      "name": "kR_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kR_z": {
+      "__class__": "ParamTocElement",
+      "ident": 142,
+      "group": "ctrlMel",
+      "name": "kR_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kw_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 143,
+      "group": "ctrlMel",
+      "name": "kw_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kw_z": {
+      "__class__": "ParamTocElement",
+      "ident": 144,
+      "group": "ctrlMel",
+      "name": "kw_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_m_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 145,
+      "group": "ctrlMel",
+      "name": "ki_m_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki_m_z": {
+      "__class__": "ParamTocElement",
+      "ident": 146,
+      "group": "ctrlMel",
+      "name": "ki_m_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "kd_omega_rp": {
+      "__class__": "ParamTocElement",
+      "ident": 147,
+      "group": "ctrlMel",
+      "name": "kd_omega_rp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_m_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 148,
+      "group": "ctrlMel",
+      "name": "i_range_m_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "i_range_m_z": {
+      "__class__": "ParamTocElement",
+      "ident": 149,
+      "group": "ctrlMel",
+      "name": "i_range_m_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "ctrlAtt": {
+    "tau_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 150,
+      "group": "ctrlAtt",
+      "name": "tau_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zeta_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 151,
+      "group": "ctrlAtt",
+      "name": "zeta_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "tau_z": {
+      "__class__": "ParamTocElement",
+      "ident": 152,
+      "group": "ctrlAtt",
+      "name": "tau_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "zeta_z": {
+      "__class__": "ParamTocElement",
+      "ident": 153,
+      "group": "ctrlAtt",
+      "name": "zeta_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "tau_rp": {
+      "__class__": "ParamTocElement",
+      "ident": 154,
+      "group": "ctrlAtt",
+      "name": "tau_rp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "mixing_factor": {
+      "__class__": "ParamTocElement",
+      "ident": 155,
+      "group": "ctrlAtt",
+      "name": "mixing_factor",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "coll_fairness": {
+      "__class__": "ParamTocElement",
+      "ident": 156,
+      "group": "ctrlAtt",
+      "name": "coll_fairness",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "cppm": {
+    "rateRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 157,
+      "group": "cppm",
+      "name": "rateRoll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ratePitch": {
+      "__class__": "ParamTocElement",
+      "ident": 158,
+      "group": "cppm",
+      "name": "ratePitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "angPitch": {
+      "__class__": "ParamTocElement",
+      "ident": 159,
+      "group": "cppm",
+      "name": "angPitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "angRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 160,
+      "group": "cppm",
+      "name": "angRoll",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "rateYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 161,
+      "group": "cppm",
+      "name": "rateYaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "hlCommander": {
+    "vtoff": {
+      "__class__": "ParamTocElement",
+      "ident": 162,
+      "group": "hlCommander",
+      "name": "vtoff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "vland": {
+      "__class__": "ParamTocElement",
+      "ident": 163,
+      "group": "hlCommander",
+      "name": "vland",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "flightmode": {
+    "althold": {
+      "__class__": "ParamTocElement",
+      "ident": 164,
+      "group": "flightmode",
+      "name": "althold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "poshold": {
+      "__class__": "ParamTocElement",
+      "ident": 165,
+      "group": "flightmode",
+      "name": "poshold",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "posSet": {
+      "__class__": "ParamTocElement",
+      "ident": 166,
+      "group": "flightmode",
+      "name": "posSet",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "yawMode": {
+      "__class__": "ParamTocElement",
+      "ident": 167,
+      "group": "flightmode",
+      "name": "yawMode",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModeRoll": {
+      "__class__": "ParamTocElement",
+      "ident": 168,
+      "group": "flightmode",
+      "name": "stabModeRoll",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModePitch": {
+      "__class__": "ParamTocElement",
+      "ident": 169,
+      "group": "flightmode",
+      "name": "stabModePitch",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stabModeYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 170,
+      "group": "flightmode",
+      "name": "stabModeYaw",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "locSrv": {
+    "enRangeStreamFP32": {
+      "__class__": "ParamTocElement",
+      "ident": 171,
+      "group": "locSrv",
+      "name": "enRangeStreamFP32",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "enLhAngleStream": {
+      "__class__": "ParamTocElement",
+      "ident": 172,
+      "group": "locSrv",
+      "name": "enLhAngleStream",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "extPosStdDev": {
+      "__class__": "ParamTocElement",
+      "ident": 173,
+      "group": "locSrv",
+      "name": "extPosStdDev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "extQuatStdDev": {
+      "__class__": "ParamTocElement",
+      "ident": 174,
+      "group": "locSrv",
+      "name": "extQuatStdDev",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "crtpsrv": {
+    "echoDelay": {
+      "__class__": "ParamTocElement",
+      "ident": 175,
+      "group": "crtpsrv",
+      "name": "echoDelay",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "kalman": {
+    "resetEstimation": {
+      "__class__": "ParamTocElement",
+      "ident": 176,
+      "group": "kalman",
+      "name": "resetEstimation",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "quadIsFlying": {
+      "__class__": "ParamTocElement",
+      "ident": 177,
+      "group": "kalman",
+      "name": "quadIsFlying",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "robustTdoa": {
+      "__class__": "ParamTocElement",
+      "ident": 178,
+      "group": "kalman",
+      "name": "robustTdoa",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "robustTwr": {
+      "__class__": "ParamTocElement",
+      "ident": 179,
+      "group": "kalman",
+      "name": "robustTwr",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "pNAcc_xy": {
+      "__class__": "ParamTocElement",
+      "ident": 180,
+      "group": "kalman",
+      "name": "pNAcc_xy",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNAcc_z": {
+      "__class__": "ParamTocElement",
+      "ident": 181,
+      "group": "kalman",
+      "name": "pNAcc_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNVel": {
+      "__class__": "ParamTocElement",
+      "ident": 182,
+      "group": "kalman",
+      "name": "pNVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNPos": {
+      "__class__": "ParamTocElement",
+      "ident": 183,
+      "group": "kalman",
+      "name": "pNPos",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pNAtt": {
+      "__class__": "ParamTocElement",
+      "ident": 184,
+      "group": "kalman",
+      "name": "pNAtt",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mNBaro": {
+      "__class__": "ParamTocElement",
+      "ident": 185,
+      "group": "kalman",
+      "name": "mNBaro",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mNGyro_rollpitch": {
+      "__class__": "ParamTocElement",
+      "ident": 186,
+      "group": "kalman",
+      "name": "mNGyro_rollpitch",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "mNGyro_yaw": {
+      "__class__": "ParamTocElement",
+      "ident": 187,
+      "group": "kalman",
+      "name": "mNGyro_yaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "initialX": {
+      "__class__": "ParamTocElement",
+      "ident": 188,
+      "group": "kalman",
+      "name": "initialX",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialY": {
+      "__class__": "ParamTocElement",
+      "ident": 189,
+      "group": "kalman",
+      "name": "initialY",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialZ": {
+      "__class__": "ParamTocElement",
+      "ident": 190,
+      "group": "kalman",
+      "name": "initialZ",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "initialYaw": {
+      "__class__": "ParamTocElement",
+      "ident": 191,
+      "group": "kalman",
+      "name": "initialYaw",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxPos": {
+      "__class__": "ParamTocElement",
+      "ident": 192,
+      "group": "kalman",
+      "name": "maxPos",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "maxVel": {
+      "__class__": "ParamTocElement",
+      "ident": 193,
+      "group": "kalman",
+      "name": "maxVel",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "health": {
+    "startPropTest": {
+      "__class__": "ParamTocElement",
+      "ident": 194,
+      "group": "health",
+      "name": "startPropTest",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "startBatTest": {
+      "__class__": "ParamTocElement",
+      "ident": 195,
+      "group": "health",
+      "name": "startBatTest",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "propTestPWMRatio": {
+      "__class__": "ParamTocElement",
+      "ident": 196,
+      "group": "health",
+      "name": "propTestPWMRatio",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "memTst": {
+    "resetW": {
+      "__class__": "ParamTocElement",
+      "ident": 197,
+      "group": "memTst",
+      "name": "resetW",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "posCtrlIndi": {
+    "K_xi_x": {
+      "__class__": "ParamTocElement",
+      "ident": 198,
+      "group": "posCtrlIndi",
+      "name": "K_xi_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_xi_y": {
+      "__class__": "ParamTocElement",
+      "ident": 199,
+      "group": "posCtrlIndi",
+      "name": "K_xi_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_xi_z": {
+      "__class__": "ParamTocElement",
+      "ident": 200,
+      "group": "posCtrlIndi",
+      "name": "K_xi_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_x": {
+      "__class__": "ParamTocElement",
+      "ident": 201,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_x",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_y": {
+      "__class__": "ParamTocElement",
+      "ident": 202,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_y",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "K_dxi_z": {
+      "__class__": "ParamTocElement",
+      "ident": 203,
+      "group": "posCtrlIndi",
+      "name": "K_dxi_z",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pq_clamping": {
+      "__class__": "ParamTocElement",
+      "ident": 204,
+      "group": "posCtrlIndi",
+      "name": "pq_clamping",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "posCtlPid": {
+    "xKp": {
+      "__class__": "ParamTocElement",
+      "ident": 205,
+      "group": "posCtlPid",
+      "name": "xKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xKi": {
+      "__class__": "ParamTocElement",
+      "ident": 206,
+      "group": "posCtlPid",
+      "name": "xKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xKd": {
+      "__class__": "ParamTocElement",
+      "ident": 207,
+      "group": "posCtlPid",
+      "name": "xKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xKff": {
+      "__class__": "ParamTocElement",
+      "ident": 208,
+      "group": "posCtlPid",
+      "name": "xKff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKp": {
+      "__class__": "ParamTocElement",
+      "ident": 209,
+      "group": "posCtlPid",
+      "name": "yKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKi": {
+      "__class__": "ParamTocElement",
+      "ident": 210,
+      "group": "posCtlPid",
+      "name": "yKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKd": {
+      "__class__": "ParamTocElement",
+      "ident": 211,
+      "group": "posCtlPid",
+      "name": "yKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yKff": {
+      "__class__": "ParamTocElement",
+      "ident": 212,
+      "group": "posCtlPid",
+      "name": "yKff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKp": {
+      "__class__": "ParamTocElement",
+      "ident": 213,
+      "group": "posCtlPid",
+      "name": "zKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKi": {
+      "__class__": "ParamTocElement",
+      "ident": 214,
+      "group": "posCtlPid",
+      "name": "zKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKd": {
+      "__class__": "ParamTocElement",
+      "ident": 215,
+      "group": "posCtlPid",
+      "name": "zKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zKff": {
+      "__class__": "ParamTocElement",
+      "ident": 216,
+      "group": "posCtlPid",
+      "name": "zKff",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "thrustBase": {
+      "__class__": "ParamTocElement",
+      "ident": 217,
+      "group": "posCtlPid",
+      "name": "thrustBase",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": true
+    },
+    "thrustMin": {
+      "__class__": "ParamTocElement",
+      "ident": 218,
+      "group": "posCtlPid",
+      "name": "thrustMin",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": true
+    },
+    "rLimit": {
+      "__class__": "ParamTocElement",
+      "ident": 219,
+      "group": "posCtlPid",
+      "name": "rLimit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "pLimit": {
+      "__class__": "ParamTocElement",
+      "ident": 220,
+      "group": "posCtlPid",
+      "name": "pLimit",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "xVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 221,
+      "group": "posCtlPid",
+      "name": "xVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "yVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 222,
+      "group": "posCtlPid",
+      "name": "yVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "zVelMax": {
+      "__class__": "ParamTocElement",
+      "ident": 223,
+      "group": "posCtlPid",
+      "name": "zVelMax",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "velCtlPid": {
+    "vxKp": {
+      "__class__": "ParamTocElement",
+      "ident": 224,
+      "group": "velCtlPid",
+      "name": "vxKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vxKi": {
+      "__class__": "ParamTocElement",
+      "ident": 225,
+      "group": "velCtlPid",
+      "name": "vxKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vxKd": {
+      "__class__": "ParamTocElement",
+      "ident": 226,
+      "group": "velCtlPid",
+      "name": "vxKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vxKFF": {
+      "__class__": "ParamTocElement",
+      "ident": 227,
+      "group": "velCtlPid",
+      "name": "vxKFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKp": {
+      "__class__": "ParamTocElement",
+      "ident": 228,
+      "group": "velCtlPid",
+      "name": "vyKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKi": {
+      "__class__": "ParamTocElement",
+      "ident": 229,
+      "group": "velCtlPid",
+      "name": "vyKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKd": {
+      "__class__": "ParamTocElement",
+      "ident": 230,
+      "group": "velCtlPid",
+      "name": "vyKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vyKFF": {
+      "__class__": "ParamTocElement",
+      "ident": 231,
+      "group": "velCtlPid",
+      "name": "vyKFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKp": {
+      "__class__": "ParamTocElement",
+      "ident": 232,
+      "group": "velCtlPid",
+      "name": "vzKp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKi": {
+      "__class__": "ParamTocElement",
+      "ident": 233,
+      "group": "velCtlPid",
+      "name": "vzKi",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKd": {
+      "__class__": "ParamTocElement",
+      "ident": 234,
+      "group": "velCtlPid",
+      "name": "vzKd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vzKFF": {
+      "__class__": "ParamTocElement",
+      "ident": 235,
+      "group": "velCtlPid",
+      "name": "vzKFF",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "posEstAlt": {
+    "estAlphaAsl": {
+      "__class__": "ParamTocElement",
+      "ident": 236,
+      "group": "posEstAlt",
+      "name": "estAlphaAsl",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "estAlphaZr": {
+      "__class__": "ParamTocElement",
+      "ident": 237,
+      "group": "posEstAlt",
+      "name": "estAlphaZr",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "velFactor": {
+      "__class__": "ParamTocElement",
+      "ident": 238,
+      "group": "posEstAlt",
+      "name": "velFactor",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "velZAlpha": {
+      "__class__": "ParamTocElement",
+      "ident": 239,
+      "group": "posEstAlt",
+      "name": "velZAlpha",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "vAccDeadband": {
+      "__class__": "ParamTocElement",
+      "ident": 240,
+      "group": "posEstAlt",
+      "name": "vAccDeadband",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "powerDist": {
+    "idleThrust": {
+      "__class__": "ParamTocElement",
+      "ident": 241,
+      "group": "powerDist",
+      "name": "idleThrust",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 0,
+      "extended": true
+    }
+  },
+  "quadSysId": {
+    "thrustToTorque": {
+      "__class__": "ParamTocElement",
+      "ident": 242,
+      "group": "quadSysId",
+      "name": "thrustToTorque",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pwmToThrustA": {
+      "__class__": "ParamTocElement",
+      "ident": 243,
+      "group": "quadSysId",
+      "name": "pwmToThrustA",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "pwmToThrustB": {
+      "__class__": "ParamTocElement",
+      "ident": 244,
+      "group": "quadSysId",
+      "name": "pwmToThrustB",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "armLength": {
+      "__class__": "ParamTocElement",
+      "ident": 245,
+      "group": "quadSysId",
+      "name": "armLength",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "sensfusion6": {
+    "kp": {
+      "__class__": "ParamTocElement",
+      "ident": 246,
+      "group": "sensfusion6",
+      "name": "kp",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "ki": {
+      "__class__": "ParamTocElement",
+      "ident": 247,
+      "group": "sensfusion6",
+      "name": "ki",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": true
+    },
+    "baseZacc": {
+      "__class__": "ParamTocElement",
+      "ident": 248,
+      "group": "sensfusion6",
+      "name": "baseZacc",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "sound": {
+    "effect": {
+      "__class__": "ParamTocElement",
+      "ident": 249,
+      "group": "sound",
+      "name": "effect",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": true
+    },
+    "neffect": {
+      "__class__": "ParamTocElement",
+      "ident": 250,
+      "group": "sound",
+      "name": "neffect",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "freq": {
+      "__class__": "ParamTocElement",
+      "ident": 251,
+      "group": "sound",
+      "name": "freq",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "stabilizer": {
+    "estimator": {
+      "__class__": "ParamTocElement",
+      "ident": 252,
+      "group": "stabilizer",
+      "name": "estimator",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "controller": {
+      "__class__": "ParamTocElement",
+      "ident": 253,
+      "group": "stabilizer",
+      "name": "controller",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "stop": {
+      "__class__": "ParamTocElement",
+      "ident": 254,
+      "group": "stabilizer",
+      "name": "stop",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "cpu": {
+    "flash": {
+      "__class__": "ParamTocElement",
+      "ident": 255,
+      "group": "cpu",
+      "name": "flash",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "id0": {
+      "__class__": "ParamTocElement",
+      "ident": 256,
+      "group": "cpu",
+      "name": "id0",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "id1": {
+      "__class__": "ParamTocElement",
+      "ident": 257,
+      "group": "cpu",
+      "name": "id1",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "id2": {
+      "__class__": "ParamTocElement",
+      "ident": 258,
+      "group": "cpu",
+      "name": "id2",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    }
+  },
+  "tdoaEngine": {
+    "logId": {
+      "__class__": "ParamTocElement",
+      "ident": 259,
+      "group": "tdoaEngine",
+      "name": "logId",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "logOthrId": {
+      "__class__": "ParamTocElement",
+      "ident": 260,
+      "group": "tdoaEngine",
+      "name": "logOthrId",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "matchAlgo": {
+      "__class__": "ParamTocElement",
+      "ident": 261,
+      "group": "tdoaEngine",
+      "name": "matchAlgo",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "lighthouse": {
+    "method": {
+      "__class__": "ParamTocElement",
+      "ident": 262,
+      "group": "lighthouse",
+      "name": "method",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "bsCalibReset": {
+      "__class__": "ParamTocElement",
+      "ident": 263,
+      "group": "lighthouse",
+      "name": "bsCalibReset",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "systemType": {
+      "__class__": "ParamTocElement",
+      "ident": 264,
+      "group": "lighthouse",
+      "name": "systemType",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "bsAvailable": {
+      "__class__": "ParamTocElement",
+      "ident": 265,
+      "group": "lighthouse",
+      "name": "bsAvailable",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "sweepStd": {
+      "__class__": "ParamTocElement",
+      "ident": 266,
+      "group": "lighthouse",
+      "name": "sweepStd",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "sweepStd2": {
+      "__class__": "ParamTocElement",
+      "ident": 267,
+      "group": "lighthouse",
+      "name": "sweepStd2",
+      "ctype": "float",
+      "pytype": "<f",
+      "access": 0,
+      "extended": false
+    },
+    "enLhRawStream": {
+      "__class__": "ParamTocElement",
+      "ident": 268,
+      "group": "lighthouse",
+      "name": "enLhRawStream",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 0,
+      "extended": false
+    },
+    "lh2maxRate": {
+      "__class__": "ParamTocElement",
+      "ident": 269,
+      "group": "lighthouse",
+      "name": "lh2maxRate",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 0,
+      "extended": false
+    }
+  },
+  "firmware": {
+    "revision0": {
+      "__class__": "ParamTocElement",
+      "ident": 270,
+      "group": "firmware",
+      "name": "revision0",
+      "ctype": "uint32_t",
+      "pytype": "<L",
+      "access": 1,
+      "extended": false
+    },
+    "revision1": {
+      "__class__": "ParamTocElement",
+      "ident": 271,
+      "group": "firmware",
+      "name": "revision1",
+      "ctype": "uint16_t",
+      "pytype": "<H",
+      "access": 1,
+      "extended": false
+    },
+    "modified": {
+      "__class__": "ParamTocElement",
+      "ident": 272,
+      "group": "firmware",
+      "name": "modified",
+      "ctype": "uint8_t",
+      "pytype": "<B",
+      "access": 1,
+      "extended": false
+    }
+  }
+}
\ No newline at end of file
diff --git a/crazyflie_demos/lighthouse_openvr_tilt_control.py b/crazyflie_demos/lighthouse_openvr_tilt_control.py
index a018f05592f82d55634d61b0fcc20b0b5f3c11b9..0b64a10b548ff2f327e884ec8a49cc61ed1a6b84 100644
--- a/crazyflie_demos/lighthouse_openvr_tilt_control.py
+++ b/crazyflie_demos/lighthouse_openvr_tilt_control.py
@@ -9,7 +9,6 @@ from math import asin, atan2
 import math
 import sys
 import time
-from cv2 import EVENT_LBUTTONUP
 
 import openvr
 
@@ -21,7 +20,7 @@ from cflib.crazyflie.syncLogger import SyncLogger
 from sqlalchemy import Integer, null
 
 # URI to the Crazyflie to connect to
-uri = 'radio://0/80/2M'
+uri = 'radio://0/40/2M'
 
 print('Opening')
 vr = openvr.init(openvr.VRApplication_Other)
diff --git a/crazyflie_demos/swarm_circles.py b/crazyflie_demos/swarm_circles.py
new file mode 100644
index 0000000000000000000000000000000000000000..9ac7612c37b9cac3562668279a0dee2c0a02ae4c
--- /dev/null
+++ b/crazyflie_demos/swarm_circles.py
@@ -0,0 +1,241 @@
+# -*- coding: utf-8 -*-
+#
+#     ||          ____  _ __
+#  +------+      / __ )(_) /_______________ _____  ___
+#  | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+#  +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+#   ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+#
+#  Copyright (C) 2019 Bitcraze AB
+#
+#  This program is free software; you can redistribute it and/or
+#  modify it under the terms of the GNU General Public License
+#  as published by the Free Software Foundation; either version 2
+#  of the License, or (at your option) any later version.
+#
+#  This program is distributed in the hope that it will be useful,
+#  but WITHOUT ANY WARRANTY; without even the implied warranty of
+#  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+#  GNU General Public License for more details.
+#  You should have received a copy of the GNU General Public License
+#  along with this program; if not, write to the Free Software
+#  Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+#  MA  02110-1301, USA.
+"""
+Kitchen swarm demo
+"""
+import sys
+import time
+
+import cflib.crtp
+from cflib.crazyflie.log import LogConfig
+from cflib.crazyflie.swarm import CachedCfFactory
+from cflib.crazyflie.swarm import Swarm
+from cflib.crazyflie.syncLogger import SyncLogger
+from cflib.crazyflie.mem import MemoryElement
+from cflib.crazyflie.mem import Poly4D
+
+class Uploader:
+    def __init__(self):
+        self._is_done = False
+        self._sucess = True
+
+    def upload(self, trajectory_mem):
+        print('Uploading data')
+        trajectory_mem.write_data(self._upload_done,
+                                  write_failed_cb=self._upload_failed)
+
+        while not self._is_done:
+            time.sleep(0.2)
+
+        return self._sucess
+
+    def _upload_done(self, mem, addr):
+        print('Data uploaded')
+        self._is_done = True
+        self._sucess = True
+
+    def _upload_failed(self, mem, addr):
+        print('Data upload failed')
+        self._is_done = True
+        self._sucess = False
+
+def wait_for_position_estimator(scf):
+    print('Waiting for estimator to find position...')
+
+    log_config = LogConfig(name='Kalman Variance', period_in_ms=500)
+    log_config.add_variable('kalman.varPX', 'float')
+    log_config.add_variable('kalman.varPY', 'float')
+    log_config.add_variable('kalman.varPZ', 'float')
+
+    var_y_history = [1000] * 10
+    var_x_history = [1000] * 10
+    var_z_history = [1000] * 10
+
+    threshold = 0.001
+
+    with SyncLogger(scf, log_config) as logger:
+        for log_entry in logger:
+            data = log_entry[1]
+
+            var_x_history.append(data['kalman.varPX'])
+            var_x_history.pop(0)
+            var_y_history.append(data['kalman.varPY'])
+            var_y_history.pop(0)
+            var_z_history.append(data['kalman.varPZ'])
+            var_z_history.pop(0)
+
+            min_x = min(var_x_history)
+            max_x = max(var_x_history)
+            min_y = min(var_y_history)
+            max_y = max(var_y_history)
+            min_z = min(var_z_history)
+            max_z = max(var_z_history)
+
+            # print("{} {} {}".
+            #       format(max_x - min_x, max_y - min_y, max_z - min_z))
+
+            if (max_x - min_x) < threshold and (
+                    max_y - min_y) < threshold and (
+                    max_z - min_z) < threshold:
+                break
+
+
+def reset_estimator(scf):
+    cf = scf.cf
+    cf.param.set_value('kalman.resetEstimation', '1')
+    time.sleep(0.1)
+    cf.param.set_value('kalman.resetEstimation', '0')
+    wait_for_position_estimator(scf)
+
+
+def activate_high_level_commander(scf):
+    scf.cf.param.set_value('commander.enHighLevel', '1')
+
+
+def activate_mellinger_controller(scf, use_mellinger):
+    controller = 1
+    if use_mellinger:
+        controller = 2
+    scf.cf.param.set_value('stabilizer.controller', controller)
+
+circle =  [
+    [1.51717,0,0,0,0,1.32574,-1.98833,1.05213,-0.193077,0,0,0,0,0,0,0,0,0,0,0,0,0.535169,-0.659232,0.301615,-0.0494349,0,0,0,0,0,0,0,0],
+    [1.50824,0.3,0.106933,-0.103026,-0.0410602,-0.209442,0.212167,-0.0626071,0.00443994,0,0,0,0,0,0,0,0,0.3,0.33848,-0.00502046,-0.0275498,0.0241283,-0.151489,0.124218,-0.0286872,0,0,0,0,0,0,0,0],
+    [1.50824,0,-0.43482,-2.9983e-14,0.029862,-0.254959,0.663639,-0.450116,0.0952838,0,0,0,0,0,0,0,0,0.6,4.96303e-14,-0.0577895,1.276e-14,-0.299076,0.345641,-0.143107,0.0206168,0,0,0,0,0,0,0,0],
+    [1.51717,-0.3,0.213865,0.103026,-0.0410602,0.417628,-0.835528,0.519489,-0.105396,0,0,0,0,0,0,0,0,0.3,-0.33848,-0.01005,-0.0275498,0.0730012,0.130773,-0.146042,0.0365326,0,0,0,0,0,0,0,0],
+]
+
+small_circle =  [
+    [1.27649,0,0,0,0,1.92865,-3.47886,2.20546,-0.483774,0,0,0,0,0,0,0,0,0,0,0,0,0.69662,-1.01417,0.549531,-0.106795,0,0,0,0,0,0,0,0],
+    [1.22015,0.2,0.0606813,-0.100431,-0.0484002,-0.127439,0.0464536,0.0845032,-0.0393948,0,0,0,0,0,0,0,0,0.2,0.272864,0.000809798,-0.0324747,0.0658206,-0.360035,0.346088,-0.0967091,0,0,0,0,0,0,0,0],
+    [1.22015,0,-0.350529,-9.67329e-15,0.0352001,-0.461004,1.39941,-1.1527,0.299203,0,0,0,0,0,0,0,0,0.4,-1.22796e-15,-0.0563338,5.23403e-15,-0.505617,0.737984,-0.387096,0.0710504,0,0,0,0,0,0,0,0],
+    [1.27649,-0.2,0.172407,0.100431,-0.0484002,0.514023,-1.24746,0.930469,-0.225515,0,0,0,0,0,0,0,0,0.2,-0.272864,-0.0016548,-0.0324747,0.0991706,0.196796,-0.265897,0.0794233,0,0,0,0,0,0,0,0],
+
+]
+
+def upload_trajectory(cf, trajectory_id, trajectory):
+    trajectory_mem = cf.mem.get_mems(MemoryElement.TYPE_TRAJ)[0]
+
+    total_duration = 0
+    for row in trajectory:
+        duration = row[0]
+        x = Poly4D.Poly(row[1:9])
+        y = Poly4D.Poly(row[9:17])
+        z = Poly4D.Poly(row[17:25])
+        yaw = Poly4D.Poly(row[25:33])
+        trajectory_mem.poly4Ds.append(Poly4D(duration, x, y, z, yaw))
+        total_duration += duration
+
+    upload_result = Uploader().upload(trajectory_mem)
+    if not upload_result:
+        print('Upload failed, aborting!')
+        sys.exit(1)
+    cf.high_level_commander.define_trajectory(trajectory_id, 0,
+                                              len(trajectory_mem.poly4Ds))
+    return total_duration
+
+# _______________________________
+# Essential Functions
+# _______________________________
+
+# TAKE OFF
+DEFAULT_HEIGHT = 0.3
+SPACING = 0.25
+def take_off(scf, params):
+    cf = scf.cf
+    commander = cf.high_level_commander
+    d = params['d']
+
+    # Take off
+    commander.takeoff(DEFAULT_HEIGHT, 2.0)
+    time.sleep(3.0)
+
+    # Go to start location
+    commander.go_to( SPACING * (d-1), 0.1 -(SPACING* (d-1)), DEFAULT_HEIGHT , 0.0 ,2.0)
+    time.sleep(3.0)
+
+
+
+# Do a Loop
+LOOPS = 3
+def run_shared_sequence(scf, params):
+    cf = scf.cf
+
+    d = params['d']
+
+    commander = cf.high_level_commander
+    trajectory_id = 1
+
+    # Take off
+    duration = upload_trajectory(cf, trajectory_id, circle)
+    relative = True
+
+    # Delay based on ID
+    time.sleep((d-1)*2)
+
+    # Execute circle trajectory
+    for t in range(0, LOOPS):
+        commander.start_trajectory(trajectory_id, 1.0, relative)
+        time.sleep(duration)
+    time.sleep(4-(d-1)*2)
+
+    # Go back to initial position and land again
+    commander.go_to(SPACING * (d-1), -(SPACING* (d-1)),DEFAULT_HEIGHT , 0.0 ,2.0)
+    time.sleep(2.0)
+    commander.land(0.0, 2.0)
+    time.sleep(2)
+    commander.stop()
+
+# URIS of swarm
+uris = {
+    'radio://0/120/2M/E7E7E7E7E7',
+
+    'radio://0/90/2M/E7E7E7E7E7',
+    #'radio://0/30/2M/E7E7E7E703',
+    # Add more URIs if you want more copters in the swarm
+}
+
+# Parameters of Swarm
+params = {
+    'radio://0/120/2M/E7E7E7E7E7': [{'d': 1}],# 1
+
+    'radio://0/90/2M/E7E7E7E7E7': [{'d': 2}], #3
+    #'radio://0/30/2M/E7E7E7E703': [{'d': 3}],
+}
+
+
+if __name__ == '__main__':
+    cflib.crtp.init_drivers()
+    factory = CachedCfFactory(rw_cache='./cache')
+    with Swarm(uris, factory=factory) as swarm:
+
+        # Activate HL commander and reset estimator
+        swarm.parallel_safe(activate_high_level_commander)
+        swarm.parallel_safe(reset_estimator)
+
+        swarm.parallel_safe(take_off, args_dict=params)
+
+        input("enter to continue")
+
+        swarm.parallel_safe(run_shared_sequence, args_dict=params)
diff --git a/groundStation/gui/MicroCART/MicroCART.files b/groundStation/gui/MicroCART/MicroCART.files
index 834edd1e96f3efc25e0564d1086a6d5be87b2cca..b4d086dd0b798f2b1e94602a836172f8e25a851e 100644
--- a/groundStation/gui/MicroCART/MicroCART.files
+++ b/groundStation/gui/MicroCART/MicroCART.files
@@ -5,18 +5,13 @@ controlworker.cpp
 controlworker.h
 crazyflieworker.cpp
 crazyflieworker.h
-gamepadmonitor.cpp
-gamepadmonitor.h
 gridlines.gif
-logworker.cpp
-logworker.h
 main.cpp
 mainwindow.cpp
 mainwindow.h
 mainwindow.ui
 moc_controlworker.cpp
 moc_crazyflieworker.cpp
-moc_logworker.cpp
 moc_mainwindow.cpp
 moc_predefs.h
 moc_qFlightInstruments.cpp
diff --git a/new_quad_2022_Hardware/IMU_BreakOUT _Board/IMU_BreakOUT _Board-backups/IMU_BreakOUT _Board-2022-11-10_163734.zip b/new_quad_2022_Hardware/IMU_BreakOUT _Board/IMU_BreakOUT _Board-backups/IMU_BreakOUT _Board-2022-11-10_163734.zip
new file mode 100644
index 0000000000000000000000000000000000000000..eb7ca488615f5c2ec0de24aabf9fb840200febf1
Binary files /dev/null and b/new_quad_2022_Hardware/IMU_BreakOUT _Board/IMU_BreakOUT _Board-backups/IMU_BreakOUT _Board-2022-11-10_163734.zip differ
diff --git a/requirements.txt b/requirements.txt
new file mode 100644
index 0000000000000000000000000000000000000000..4e10059f9ec8b0f33b70ae20b4b3dc2db87f0ade
--- /dev/null
+++ b/requirements.txt
@@ -0,0 +1,8 @@
+pyserial~=3.5
+pyparsing~=2.4.7
+cflib~=0.1.21
+SQLAlchemy~=1.4.41
+matplotlib~=3.4.3
+numpy~=1.22.3
+future~=0.18.2
+pyzmq~=22.0.3
\ No newline at end of file