diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 13bc283c77c88eead0b0297c5069e468205ce552..b10138c39575da2ca1ae9f16cbe95f1f56e4c3e2 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -1,10 +1,19 @@ -build: +image: ruby:2.3 + +before_script: + - apt-get update -qq && apt-get install -y -qq libbluetooth-dev cmake + +stages: + - build + - test + +build_job: stage: build script: - bash ci-build.sh # run tests using the binary built before -test: +test_job: stage: test script: - bash ci-test.sh diff --git a/Readme.md b/Readme.md index 2180f34478f1ff3b4eed8cc54932d586fcde29eb..f8f7c607f4ea050046494ac9d5a2a28d0da279fb 100644 --- a/Readme.md +++ b/Readme.md @@ -1,3 +1,37 @@ [](https://git.ece.iastate.edu/danc/MicroCART_17-18/commits/master) -Repository for 2016-2017 MicroCART project. +# MicroCART +_Microprocessor Controlled Aerial Robotics Team_ + +**Project Statement**: "To create a modular platform for research in controls and embedded systems." + +Since 1998, MicroCART has been building aerial robots. Currently, we are +building a quadcopter that can fly autonomously. + +MicroCART has 3 areas of development: +- The quadcopter itself + - The quadcopter has been built from the ground up, incorporating a + Zybo board that provides the processor and a FPGA, an IMU sensor, motors, + props, a LiPo battery, a receiver for manual remote control, and a frame + that holds it all together. +- The ground station + - The ground station is responsible for issuing important data to the quad + (like position data from the camera system) and issuing commands to the quad + for things like configuration and path following directives. +- The Controls Model + - The quadcopter processor is programmed to implement a PID controller. We use + a Simulink model to streamline the PID tuning process and to facilitate + effective characterization of the quad. + +## Sections +[Quadcopter](quad/README.md) +[Ground Station](groundStation/README.md) +[Controls](controls/README.md) + +## Documentation +[How to demo the quadcopter](documentation/how_to_demo.md) +[How to charge the LiPo batteries](documentation/how_to_charge_lipo.md) +[Continuous Integration (automatic build process) FAQ](documentation/ci_faq.md) + +# Stable Releases +To browse stable releases from previous teams, view the [Tags](/../tags). \ No newline at end of file diff --git a/ci-build.sh b/ci-build.sh index 3d236441d6664bac2dc512112ddc10742d3e9991..36b584f4ad5f6e7e876ba7f0c8b41e68ebbc2c7e 100644 --- a/ci-build.sh +++ b/ci-build.sh @@ -3,5 +3,8 @@ set -e # Quad Libraries and Boot image -(cd quad && make) -#(cd groundStation && make) +(cd quad && make deep-clean && make) + +# Ground station +git submodule update --init --recursive +(cd groundStation && make vrpn && make) diff --git a/ci-test.sh b/ci-test.sh index 4504f9a6d9d422964da0fc469bcba52befdb65e2..67e6ed1c6afc9968d791978dbdf4cfca8f9711eb 100644 --- a/ci-test.sh +++ b/ci-test.sh @@ -3,4 +3,4 @@ set -e # Quad -cd quad && make && make test +(cd quad && make test) diff --git a/controls/DataAnalysisTool/Tool/simplePlots.m b/controls/DataAnalysisTool/Tool/simplePlots.m index edd91bf4aa05002531109897c7c0f6ca162ed387..dfe97b5ae055d0de80f55dc94c284c8affe19eb7 100644 --- a/controls/DataAnalysisTool/Tool/simplePlots.m +++ b/controls/DataAnalysisTool/Tool/simplePlots.m @@ -38,22 +38,22 @@ legend('Pitch Error', 'Pitch PID output'); linkaxes([ax1, ax2], 'x'); %% ax2 = subplot(2,2,1); -plot(time, XSetpointConstant - VRPNXConstant); +plot(expData.Time.data, expData.X_Setpoint_Constant.data - expData.VRPN_X_Constant.data); title('X error'); ax1 = subplot(2,2,2); -plot(time, XposPIDCorrection); +plot(expData.Time.data, expData.X_pos_PID_Correction.data); title('x output'); ax3 = subplot(2,2,3); -plot(time, PitchPIDCorrection); hold on; -plot(time, VRPNPitchConstant .* 10); +plot(expData.Time.data, expData.Pitch_PID_Correction.data); hold on; +plot(expData.Time.data, expData.VRPN_Pitch_Constant.data .* 10); title('pitch output'); legend('output', 'Pitch'); ax4 = subplot(2,2,4); -plot(time, PitchRatePIDCorrection); hold on; -plot(time, gyro_y .* 1044.26); +plot(expData.Time.data, expData.Pitch_Rate_PID_Correction.data); hold on; +plot(expData.Time.data, expData.gyro_y.data .* 1044.26); legend('output', 'Pitch rate'); title('pitch rate output'); @@ -67,4 +67,43 @@ plot(time, YawConstant); ax1 = subplot(2, 1, 2); plot(time, gyro_z); hold on; plot(time, YawRatePIDCorrection); -linkaxes([ax1, ax2], 'x'); \ No newline at end of file +linkaxes([ax1, ax2], 'x'); + +%% +all_motors = expData.Signal_Mixer_PWM_0.data + expData.Signal_Mixer_PWM_1.data + ... + expData.Signal_Mixer_PWM_2.data + expData.Signal_Mixer_PWM_3.data; +ax1 = subplot(1, 2, 1); +plot(expData.Time.data, all_motors ./ 4); hold on; +plot(expData.Time.data, expData.RC_Throttle_Constant.data); hold on; +plot(expData.Time.data, expData.Pitch_Rate_PID_Correction.data); hold on; +plot(expData.Time.data, expData.Roll_Rate_PID_Correction.data); hold on; +plot(expData.Time.data, expData.Yaw_Rate_PID_Correction.data); +legend('average motors', 'throttle', 'pitch', 'roll', 'yaw'); +ax2 = subplot(1, 2, 2); +plot(expData.Time.data, -expData.VRPN_Alt_Constant.data); +legend('Z, meters'); +linkaxes([ax1, ax2], 'x'); + +%% +ax1 = subplot(1, 2, 1); +plot(expData.Time.data, expData.Pitch_Constant.data .* (180 / pi)); hold on; grid minor +plot(expData.Time.data, expData.VRPN_Pitch_Constant.data .* (180 / pi)); +legend('imu', 'vrpn'); +ax2 = subplot(1, 2, 2); +plot(expData.Time.data, expData.Roll_Constant.data .* (180 / pi)); hold on; grid minor +plot(expData.Time.data, expData.VRPN_Roll_Constant.data .* (180 / pi)); +legend('imu', 'vrpn'); +linkaxes([ax1, ax2], 'x'); + +%% +vrpn_roll_d = diff(expData.VRPN_Roll_Constant.data) / 0.005; +plot(expData.Time.data, [0; vrpn_roll_d] .* (180 / pi)); hold on; grid minor; +plot(expData.Time.data, expData.gyro_x.data .* (180 / pi)); +%% +ax1 = subplot(3, 1, 1); +plot(expData.Time.data, expData.gyro_x.data); +ax2 = subplot(3, 1, 2); +plot(expData.Time.data, expData.gyro_y.data); +ax3 = subplot(3, 1, 3); +plot(expData.Time.data, expData.gyro_z.data); +linkaxes([ax1, ax2, ax3], 'x'); diff --git a/controls/README.md b/controls/README.md new file mode 100644 index 0000000000000000000000000000000000000000..456ed8fa19fc7eadf759c1bcef4e33d3bffdbb7b --- /dev/null +++ b/controls/README.md @@ -0,0 +1,3 @@ +# Controls + +_TODO_ \ No newline at end of file diff --git a/controls/dataCollection/IMU_standstill/analyzeIMU_data.m b/controls/dataCollection/IMU_standstill/analyzeIMU_data.m new file mode 100644 index 0000000000000000000000000000000000000000..9d4429866238289dbb2836e3913552c819c82b0d --- /dev/null +++ b/controls/dataCollection/IMU_standstill/analyzeIMU_data.m @@ -0,0 +1,273 @@ +function analyzeIMU_data( fileName ) +%UNTITLED2 Summary of this function goes here +% Detailed explanation goes here + + + IMU_dataDirectory = 'C:\Users\Tara\Desktop\Project Documents\Current Project Documents\EE 492\Data\IMU Data'; + IMU_dataFile = [IMU_dataDirectory , '\' , fileName]; + + IMU_data = readtable(IMU_dataFile); + + g = 9.8; %meters per second squared + + %Set the column values of the table + timeCol = 1; + accelXCol = 2; + accelYCol = 3; + accelZCol = 4; + gyroXCol = 5; + gyroYCol = 6; + gyroZCol = 7; + + %Pull the data columns into arrays + timeArray = IMU_data{:, timeCol}; + accelXArray = IMU_data{:, accelXCol}; + accelYArray = IMU_data{:, accelYCol}; + accelZArray = IMU_data{:, accelZCol}; + gyroXArray = IMU_data{:, gyroXCol}; + gyroYArray = IMU_data{:, gyroYCol}; + gyroZArray = IMU_data{:, gyroZCol}; + + %Get the mean and standard deviation of the accelerometer data and multiply + %by the g constant to get this value in meters per second + accelX_mean = mean(accelXArray) * g; + accelY_mean = mean(accelYArray) * g; + accelZ_mean = mean(accelZArray) * g + accelX_dev = std(accelXArray) * g; + accelY_dev = std(accelYArray) * g; + accelZ_dev = std(accelZArray) * g; + + %Get mean and standard deviation of gyroscope data, which is in rad / sec + gyroX_mean = mean(gyroXArray); + gyroY_mean = mean(gyroYArray); + gyroZ_mean = mean(gyroZArray); + gyroX_dev = std(gyroXArray); + gyroY_dev = std(gyroYArray); + gyroZ_dev = std(gyroZArray); + + %Calculate the variances from the standard deviations + accelX_var = accelX_dev ^ 2; + accelY_var = accelY_dev ^ 2; + accelZ_var = accelZ_dev ^ 2; + gyroX_var = gyroX_dev ^ 2; + gyroY_var = gyroY_dev ^ 2; + gyroZ_var = gyroZ_dev ^ 2; + + %Print received data from accelerometer nicely to command prompt + disp( ' ' ); + disp('Accelerometer data: '); + disp( [ 'X acceleration mean ( m / s^2 ): ' , num2str(accelX_mean) ] ); + disp( [ 'Y acceleration mean ( m / s^2 ): ' , num2str(accelY_mean) ] ); + disp( [ 'Z acceleration mean ( m / s^2 ): ' , num2str(accelZ_mean) ] ); + disp( [ 'X acceleration standard deviation ( m / s^2 ): ' , num2str(accelX_dev) ] ); + disp( [ 'Y acceleration standard deviation ( m / s^2 ): ' , num2str(accelY_dev) ] ); + disp( [ 'Z acceleration standard deviation ( m / s^2 ): ' , num2str(accelZ_dev) ] ); + disp( [ 'X acceleration variance ( (m/s^2) ^ 2 ): ', num2str(accelX_var) ] ); + disp( [ 'Y acceleration variance ( (m/s^2) ^ 2 ): ', num2str(accelY_var) ] ); + disp( [ 'Z acceleration variance ( (m/s^2) ^ 2 ): ', num2str(accelZ_var) ] ); + disp( ' ' ); + + + %Print received data from gyroscope nicely to command prompt + disp('Gyroscope data: '); + disp( [ 'Angular velocity about X mean ( rad / s ): ' , num2str(gyroX_mean) ] ); + disp( [ 'Angular velocity about Y mean ( rad / s ): ' , num2str(gyroY_mean) ] ); + disp( [ 'Angular velocity about Z mean ( rad / s ): ' , num2str(gyroZ_mean) ] ); + disp( [ 'Angular velocity about X standard deviation ( rad / s ): ' , num2str(gyroX_dev) ] ); + disp( [ 'Angular velocity about Y standard deviation ( rad / s ): ' , num2str(gyroY_dev) ] ); + disp( [ 'Angular velocity about Z standard deviation ( rad / s ): ' , num2str(gyroZ_dev) ] ); + disp( [ 'Angular velocity about X variance ( (rad/s) ^ 2 ): ', num2str(gyroX_var) ] ); + disp( [ 'Angular velocity about Y variance ( (rad/s) ^ 2 ): ', num2str(gyroY_var) ] ); + disp( [ 'Angular velocity about Z variance ( (rad/s) ^ 2 ): ', num2str(gyroZ_var) ] ); + disp( ' ' ); + +% %Graph plots: +% figure(); +% plot(timeArray, accelXArray * g); +% title('X Acceleration Data ( m / s^2 )'); +% xlabel('Time (s)'); +% +% figure(); +% plot(timeArray, accelYArray * g); +% title('Y Acceleration Data ( m / s^2 )'); +% xlabel('Time (s)'); +% +% figure(); +% plot(timeArray, accelZArray * g); +% title('Z Acceleration Data ( m / s^2 )'); +% xlabel('Time (s)'); +% +% figure(); +% plot(timeArray, gyroXArray); +% title('Angular Velocity about X Data (rad/s)'); +% xlabel('Time (s)'); +% +% figure(); +% plot(timeArray, gyroYArray); +% title('Angular Velocity about Y Data (rad/s)'); +% xlabel('Time (s)'); +% +% figure(); +% plot(timeArray, gyroZArray); +% title('Angular Velocity about Z Data (rad/s)'); +% xlabel('Time (s)'); +% +% +% %Get the magnitude of the accelerometer data +% mag_accel = sqrt( accelXArray.^2 + accelYArray.^2 + accelZArray.^2 ) * g; +% mag_accel_mean = mean( mag_accel ); +% mag_accel_dev = std( mag_accel ); +% mag_accel_var = mag_accel_dev ^ 2; +% +% %Display these results and graph them +% disp( ['Magnitude of acceleration vector mean ( m / s^2 ): ' , num2str(mag_accel_mean) ] ); +% disp( ['Magnitude of acceleration vector standard deviation ( m / s^2 ): ' , num2str(mag_accel_dev) ] ); +% disp( ['Magnitude of acceleration vector variance ( ( m/s^2 )^2 ): ' , num2str(mag_accel_var) ] ); +% figure(); +% plot( timeArray, mag_accel, 'b' ); +% hold on; +% plot( timeArray, ones(1, length(timeArray)) * g , 'r-' ); +% title('Magnitude of Acceleration Vector with Respect to Nominal ( m / s^2 )'); +% xlabel('Time (s)'); +% legend( 'Accel Mag Measured' , 'Accel Mag Nominal' ); +% +% %Also graph the percent error +% mag_accel_percentError = abs(mag_accel - g) / g * 100; +% figure(); +% plot( timeArray, mag_accel_percentError); +% title('Magnitude of Acceleration Vector Percent Error from Nominal (%) '); +% xlabel('Time (s)'); +% ylabel('Percent Error (%)'); +% +% mag_accel_percentError_mean = mean( mag_accel_percentError ); +% mag_accel_percentError_dev = std( mag_accel_percentError ); +% +% disp(' '); +% disp( ['Percent error from nominal mean ( % ): ' , num2str(mag_accel_percentError_mean) ] ); +% disp( ['Percent error from nominal standard deviation ( % ): ' , num2str(mag_accel_percentError_dev) ] ); +% disp(' '); + + + + + + %Following example given in MATLAB help + %Looking at the frequency response characterisitcs of the noise + timeArray_diff = diff( timeArray ); + timeArray_diffMean = mean( timeArray_diff ); %seconds + fs = 1 / timeArray_diffMean; + + %Get the fast fourier transform + accelX_fft = fft( accelXArray*g - accelX_mean ); + accelY_fft = fft( accelYArray*g - accelY_mean ); + accelZ_fft = fft( accelZArray*g - accelZ_mean ); + gyroX_fft = fft( gyroXArray - gyroX_mean ); + gyroY_fft = fft( gyroYArray - gyroY_mean ); + gyroZ_fft = fft( gyroZArray - gyroZ_mean ); + + %Determine the length of our data and obtain only first half of FFT data + N = length(timeArray); + accelX_fft = accelX_fft( 1:N/2+1 ); + accelY_fft = accelY_fft( 1:N/2+1 ); + accelZ_fft = accelZ_fft( 1:N/2+1 ); + gyroX_fft = gyroX_fft( 1:N/2+1 ); + gyroY_fft = gyroY_fft( 1:N/2+1 ); + gyroZ_fft = gyroZ_fft( 1:N/2+1 ); + + %Get the power spectral density of the signal + accelX_PSD = ( 1 / (2*pi*N) ) * abs( accelX_fft ) .^ 2; + accelY_PSD = ( 1 / (2*pi*N) ) * abs( accelY_fft ) .^ 2; + accelZ_PSD = ( 1 / (2*pi*N) ) * abs( accelZ_fft ) .^ 2; + gyroX_PSD = ( 1 / (2*pi*N) ) * abs( gyroX_fft ) .^ 2; + gyroY_PSD = ( 1 / (2*pi*N) ) * abs( gyroY_fft ) .^ 2; + gyroZ_PSD = ( 1 / (2*pi*N) ) * abs( gyroZ_fft ) .^ 2; + + %Multiply everything but the first and last term by 2 + accelX_PSD(2:end-1) = 2*accelX_PSD(2:end-1); + accelY_PSD(2:end-1) = 2*accelY_PSD(2:end-1); + accelZ_PSD(2:end-1) = 2*accelZ_PSD(2:end-1); + gyroX_PSD(2:end-1) = 2*gyroX_PSD(2:end-1); + gyroY_PSD(2:end-1) = 2*gyroY_PSD(2:end-1); + gyroZ_PSD(2:end-1) = 2*gyroZ_PSD(2:end-1); + + %Get the frequency range vector + freq = 0:(2*pi)/N:pi; + + %Show the plots of the power spectral density in the log domain + figure(); + plot( freq/pi, 10*log10(accelX_PSD) ); + %plot( freq/pi, accelX_PSD, '*' ); + title('Periodogram of X Acceleration Data Using FFT'); + xlabel('Normalized Frequency (\times\pi rad/sample)'); + ylabel('Power Frequency (dB/rad/sample)'); + %ylabel('Power Frequency'); + + figure(); + plot( freq/pi, 10*log10(accelY_PSD) ); + title('Periodogram of Y Acceleration Data Using FFT'); + xlabel('Normalized Frequency (\times\pi rad/sample)'); + ylabel('Power Frequency (dB/rad/sample)'); + + figure(); + plot( freq/pi, 10*log10(accelZ_PSD) ); + title('Periodogram of Z Acceleration Data Using FFT'); + xlabel('Normalized Frequency (\times\pi rad/sample)'); + ylabel('Power Frequency (dB/rad/sample)'); + + figure(); + plot( freq/pi, 10*log10(gyroX_PSD) ); + title('Periodogram of Angular Velocity about X Data Using FFT'); + xlabel('Normalized Frequency (\times\pi rad/sample)'); + ylabel('Power Frequency (dB/rad/sample)'); + + figure(); + plot( freq/pi, 10*log10(gyroY_PSD) ); + title('Periodogram of Angular Velocity about Y Using FFT'); + xlabel('Normalized Frequency (\times\pi rad/sample)'); + ylabel('Power Frequency (dB/rad/sample)'); + + figure(); + plot( freq/pi, 10*log10(gyroZ_PSD) ); + title('Periodogram of Angular Velocity about Z Using FFT'); + xlabel('Normalized Frequency (\times\pi rad/sample)'); + ylabel('Power Frequency (dB/rad/sample)'); + + + + %Estimate the average power spectral density, ignoring the first value + accelX_PSD_mean = mean( accelX_PSD(2:end) ); + accelX_PSD_mean_dB = 10*log10( accelX_PSD_mean ); + accelY_PSD_mean = mean( accelY_PSD(2:end) ); + accelY_PSD_mean_dB = 10*log10( accelY_PSD_mean ); + accelZ_PSD_mean = mean( accelZ_PSD(2:end) ); + accelZ_PSD_mean_dB = 10*log10( accelZ_PSD_mean ); + gyroX_PSD_mean = mean( gyroX_PSD(2:end) ); + gyroX_PSD_mean_dB = 10*log10( gyroX_PSD_mean ); + gyroY_PSD_mean = mean( gyroY_PSD(2:end) ); + gyroY_PSD_mean_dB = 10*log10( gyroY_PSD_mean ); + gyroZ_PSD_mean = mean( gyroZ_PSD(2:end) ); + gyroZ_PSD_mean_dB = 10*log10( gyroZ_PSD_mean ); + + %Display the average power spectral densities in dB + disp( ' ' ); + disp( [ 'Average PSD for X Acceleration Data Noise (dB): ' , num2str(accelX_PSD_mean_dB) ] ); + disp( [ 'Average PSD for Y Acceleration Data Noise (dB): ' , num2str(accelY_PSD_mean_dB) ] ); + disp( [ 'Average PSD for Z Acceleration Data Noise (dB): ' , num2str(accelZ_PSD_mean_dB) ] ); + disp( [ 'Average PSD for Angular Velocity about X Data Noise (dB): ' , num2str(gyroX_PSD_mean_dB) ] ); + disp( [ 'Average PSD for Angular Velocity about Y Data Noise (dB): ' , num2str(gyroY_PSD_mean_dB) ] ); + disp( [ 'Average PSD for Angular Velocity about Z Data Noise (dB): ' , num2str(gyroZ_PSD_mean_dB) ] ); + disp( ' ' ); + + disp( ' ' ); + disp( [ 'Average PSD for X Acceleration Data Noise : ' , num2str(accelX_PSD_mean) ] ); + disp( [ 'Average PSD for Y Acceleration Data Noise : ' , num2str(accelY_PSD_mean) ] ); + disp( [ 'Average PSD for Z Acceleration Data Noise : ' , num2str(accelZ_PSD_mean) ] ); + disp( [ 'Average PSD for Angular Velocity about X Data Noise : ' , num2str(gyroX_PSD_mean) ] ); + disp( [ 'Average PSD for Angular Velocity about Y Data Noise : ' , num2str(gyroY_PSD_mean) ] ); + disp( [ 'Average PSD for Angular Velocity about Z Data Noise : ' , num2str(gyroZ_PSD_mean) ] ); + disp( ' ' ); + + + +end + diff --git a/controls/model/Quadcopter_Model_R2015_A.mdl b/controls/model/Quadcopter_Model_R2015_A.mdl index 1ce8804095f97383c65bf5506d2a66c794009662..dc185578f51fa469a8f1b8fb5900bf19a33b89bc 100644 --- a/controls/model/Quadcopter_Model_R2015_A.mdl +++ b/controls/model/Quadcopter_Model_R2015_A.mdl @@ -6,7 +6,7 @@ Model { NumRootInports 0 NumRootOutports 0 ParameterArgumentNames "" - ComputedModelVersion "1.351" + ComputedModelVersion "1.2982" NumModelReferences 0 NumTestPointedSignals 0 } @@ -19,6 +19,7 @@ Model { MinMaxOverflowArchiveMode "Overwrite" FPTRunName "Run 1" MaxMDLFileLineLength 120 + InitFcn "clear mex\ndelete test_model_sfun.mexw64" Object { $PropName "BdWindowsInfo" $ObjectID 1 @@ -43,48 +44,66 @@ Model { $PropName "ExplorerBarInfo" $ObjectID 4 $ClassName "Simulink.ExplorerBarInfo" - Visible [1] + Visible [0] } Array { Type "Simulink.EditorInfo" - Dimension 2 + Dimension 4 Object { $ObjectID 5 IsActive [0] - ViewObjType "SimulinkSubsys" - LoadSaveID "541" - Extents [1755.0, 874.0] - ZoomFactor [1.5] - Offset [-408.3367559523798, 164.59047619047868] + ViewObjType "SimulinkTopLevel" + LoadSaveID "0" + Extents [1755.0, 904.0] + ZoomFactor [1.0] + Offset [336.19666666666762, 144.20000000000005] } Object { $ObjectID 6 IsActive [1] - ViewObjType "SimulinkTopLevel" - LoadSaveID "0" - Extents [1755.0, 874.0] - ZoomFactor [1.5] - Offset [661.09523809523807, 324.57142857142884] + ViewObjType "SimulinkSubsys" + LoadSaveID "573" + Extents [1755.0, 904.0] + ZoomFactor [0.8] + Offset [-151.38571428571572, -12.602379760288613] + } + Object { + $ObjectID 7 + IsActive [0] + ViewObjType "SimulinkSubsys" + LoadSaveID "650" + Extents [1755.0, 904.0] + ZoomFactor [0.5] + Offset [383.52935415893444, -40.361112608789426] + } + Object { + $ObjectID 8 + IsActive [0] + ViewObjType "SimulinkSubsys" + LoadSaveID "436" + Extents [1755.0, 904.0] + ZoomFactor [1.25] + Offset [716.49880952381045, 116.5285714285709] } PropName "EditorsInfo" } } } - Created "Mon Oct 17 15:29:19 2016" + Created "Thu Nov 03 18:34:52 2016" Creator "Andy" UpdateHistory "UpdateHistoryNever" ModifiedByFormat "%<Auto>" LastModifiedBy "Andy" ModifiedDateFormat "%<Auto>" - LastModifiedDate "Mon Dec 05 22:25:03 2016" - RTWModifiedTimeStamp 402877502 - ModelVersionFormat "1.%<AutoIncrement:351>" + LastModifiedDate "Tue Apr 04 18:41:22 2017" + RTWModifiedTimeStamp 413232081 + ModelVersionFormat "1.%<AutoIncrement:2982>" ConfigurationManager "none" - SampleTimeColors off + SampleTimeColors on SampleTimeAnnotations off LibraryLinkDisplay "disabled" WideLines off - ShowLineDimensions off + ShowLineDimensions on ShowPortDataTypes off ShowDesignRanges off ShowLoopsOnError on @@ -119,7 +138,7 @@ Model { TryForcingSFcnDF off Object { $PropName "DataLoggingOverride" - $ObjectID 8 + $ObjectID 10 $ClassName "Simulink.SimulationData.ModelLoggingInfo" model_ "Quadcopter_Model_R2015_A" overrideMode_ [0.0] @@ -136,12 +155,6 @@ Model { PropName "logAsSpecifiedByModelsSSIDs_" } } - Object { - $PropName "InstrumentedSignals" - $ObjectID 9 - $ClassName "Simulink.HMI.InstrumentedSignals" - Persistence [] - } RecordCoverage off CovPath "/" CovSaveName "covdata" @@ -190,16 +203,16 @@ Model { Type "Handle" Dimension 1 Simulink.ConfigSet { - $ObjectID 10 + $ObjectID 11 Version "1.15.0" Array { Type "Handle" Dimension 8 Simulink.SolverCC { - $ObjectID 11 + $ObjectID 12 Version "1.15.0" StartTime "0.0" - StopTime "20" + StopTime "runtime" AbsTol "auto" FixedStep "auto" InitialStep "auto" @@ -231,7 +244,7 @@ Model { InsertRTBMode "Whenever possible" } Simulink.DataIOCC { - $ObjectID 12 + $ObjectID 13 Version "1.15.0" Decimation "1" ExternalInput "[t, u]" @@ -264,7 +277,7 @@ Model { Refine "1" } Simulink.OptimizationCC { - $ObjectID 13 + $ObjectID 14 Version "1.15.0" Array { Type "Cell" @@ -321,7 +334,7 @@ Model { AccelVerboseBuild off } Simulink.DebuggingCC { - $ObjectID 14 + $ObjectID 15 Version "1.15.0" RTPrefix "error" ConsistencyChecking "none" @@ -331,7 +344,7 @@ Model { ReadBeforeWriteMsg "UseLocalSettings" WriteAfterWriteMsg "UseLocalSettings" WriteAfterReadMsg "UseLocalSettings" - AlgebraicLoopMsg "warning" + AlgebraicLoopMsg "error" ArtificialAlgebraicLoopMsg "warning" SaveWithDisabledLinksMsg "warning" SaveWithParameterizedLinksMsg "warning" @@ -409,7 +422,7 @@ Model { IntegerSaturationMsg "warning" } Simulink.HardwareCC { - $ObjectID 15 + $ObjectID 16 Version "1.15.0" ProdBitPerChar 8 ProdBitPerShort 16 @@ -449,9 +462,9 @@ Model { ProdEqTarget on } Simulink.ModelReferenceCC { - $ObjectID 16 + $ObjectID 17 Version "1.15.0" - UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + UpdateModelReferenceTargets "Force" CheckModelReferenceTargetMessage "error" EnableParallelModelReferenceBuilds off ParallelModelReferenceErrorOnInvalidPool on @@ -464,8 +477,12 @@ Model { SupportModelReferenceSimTargetCustomCode off } Simulink.SFSimCC { - $ObjectID 17 + $ObjectID 18 Version "1.15.0" + SimCustomHeaderCode "#include \"complementary_filter.h\"\n#include \"aeb_mat.h\"\n#include \"angle_accel.h\"" + SimUserSources "complementary_filter.c\naeb_mat.c\nangle_accel.c" + SimUserIncludeDirs "../../quad/src/computation_graph\n../../quad/src/quad_app\n../../quad/src/graph_blocks\n../.." + "/quad/src/commands" SFSimEcho on SimCtrlC on SimIntegrity on @@ -476,7 +493,7 @@ Model { } Simulink.RTWCC { $BackupClass "Simulink.RTWCC" - $ObjectID 18 + $ObjectID 19 Version "1.15.0" Array { Type "Cell" @@ -514,7 +531,7 @@ Model { TLCAssert off RTWUseLocalCustomCode off RTWUseSimCustomCode off - Toolchain "Automatically locate an installed toolchain" + Toolchain "MinGW64 v4.x | gmake (64-bit Windows)" BuildConfiguration "Faster Builds" IncludeHyperlinkInReport off LaunchReport off @@ -544,7 +561,7 @@ Model { Type "Handle" Dimension 2 Simulink.CodeAppCC { - $ObjectID 19 + $ObjectID 20 Version "1.15.0" Array { Type "Cell" @@ -617,7 +634,7 @@ Model { } Simulink.GRTTargetCC { $BackupClass "Simulink.TargetCC" - $ObjectID 20 + $ObjectID 21 Version "1.15.0" Array { Type "Cell" @@ -707,17 +724,17 @@ Model { } Name "Configuration" CurrentDlgPage "Solver" - ConfigPrmDlgPosition [ 195, 142, 1085, 882 ] + ConfigPrmDlgPosition [ 510, 71, 1400, 811 ] } PropName "ConfigurationSets" } Simulink.ConfigSet { $PropName "ActiveConfigurationSet" - $ObjectID 10 + $ObjectID 11 } Object { $PropName "DataTransfer" - $ObjectID 22 + $ObjectID 23 $ClassName "Simulink.GlobalDataTransfer" DefaultTransitionBetweenSyncTasks "Ensure deterministic transfer (maximum delay)" DefaultTransitionBetweenAsyncTasks "Ensure data integrity only" @@ -825,6 +842,74 @@ Model { DisplayOption "none" BusSelectionMode off } + Block { + BlockType DiscreteFilter + NumeratorSource "Dialog" + Numerator "[1]" + DenominatorSource "Dialog" + Denominator "[1 0.5]" + InitialStatesSource "Dialog" + InitialStates "0" + InputProcessing "Elements as channels (sample based)" + ExternalReset "None" + InitialDenominatorStates "0" + FilterStructure "Direct form II" + SampleTime "-1" + a0EqualsOne off + NumCoefMin "[]" + NumCoefMax "[]" + DenCoefMin "[]" + DenCoefMax "[]" + OutMin "[]" + OutMax "[]" + StateDataTypeStr "Inherit: Same as input" + MultiplicandDataTypeStr "Inherit: Same as input" + NumCoefDataTypeStr "Inherit: Inherit via internal rule" + DenCoefDataTypeStr "Inherit: Inherit via internal rule" + NumProductDataTypeStr "Inherit: Inherit via internal rule" + DenProductDataTypeStr "Inherit: Inherit via internal rule" + NumAccumDataTypeStr "Inherit: Inherit via internal rule" + DenAccumDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow off + StateMustResolveToSignalObject off + RTWStateStorageClass "Auto" + } + Block { + BlockType DiscreteIntegrator + IntegratorMethod "Integration: Forward Euler" + gainval "1.0" + ExternalReset "none" + InitialConditionSource "internal" + InitialCondition "0" + InitialConditionSetting "Output" + SampleTime "1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Inherit via internal rule" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow off + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + ShowSaturationPort off + ShowStatePort off + IgnoreLimit off + StateMustResolveToSignalObject off + RTWStateStorageClass "Auto" + } + Block { + BlockType FromWorkspace + VariableName "simulink_input" + OutDataTypeStr "Inherit: auto" + SampleTime "-1" + Interpolate on + ZeroCross off + OutputAfterFinalValue "Extrapolation" + } Block { BlockType Gain Gain "1" @@ -933,6 +1018,21 @@ Model { SFunctionModules "''" PortCounts "[]" } + Block { + BlockType Saturate + UpperLimitSource "Dialog" + UpperLimit "0.5" + LowerLimitSource "Dialog" + LowerLimit "-0.5" + LinearizeAsGain on + ZeroCross on + SampleTime "-1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as input" + LockScale off + RndMeth "Floor" + } Block { BlockType Scope Floating off @@ -997,6 +1097,26 @@ Model { Block { BlockType Terminator } + Block { + BlockType ToWorkspace + VariableName "simulink_output" + MaxDataPoints "1000" + Decimation "1" + SaveFormat "Array" + Save2DSignal "Inherit from input (this choice will be removed - see release notes)" + FixptAsFi off + NumInputs "1" + SampleTime "0" + } + Block { + BlockType TransportDelay + DelayTime "1" + InitialOutput "0" + BufferSize "1024" + FixedBuffer off + TransDelayFeedthrough off + PadeOrder "0" + } Block { BlockType ZeroOrderHold SampleTime "1" @@ -1016,31 +1136,31 @@ Model { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "150" + ZoomFactor "100" ReportName "simulink-default.rpt" - SIDHighWatermark "1020" + SIDHighWatermark "1424" Block { BlockType SubSystem - Name "\n\n\n\n\n\n" - SID "541" - Ports [4, 6] - Position [1155, 479, 1350, 711] - ZOrder 67 + Name " Sensors " + SID "650" + Ports [6, 3] + Position [1300, 422, 1520, 658] + ZOrder 73 + ShowName off RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 23 + $ObjectID 24 $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Rotor 1 Duty Cycle', 'texmode', 'on');\nport_label('input', 2, 'Rotor 2 Duty Cycle" - "', 'texmode', 'on');\nport_label('input', 3, 'Rotor 3 Duty Cycle', 'texmode', 'on');\nport_label('input', 4, 'Rotor 4" - " Duty Cycle', 'texmode', 'on');\nport_label('output', 1, '^{B}Omega', 'texmode', 'on');\nport_label('output', 2, '\\T" - "heta', 'texmode', 'on');\nport_label('output', 3, '^{B}v_o', 'texmode', 'on');\nport_label('output', 4, '^{E}r_o', 't" - "exmode', 'on');\nport_label('output', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('output', 6, '^{B}g', 'texmode'" - ", 'on');\ndisp('Actuation', 'texmode', 'on'); " + Display "port_label('input', 1, '^{B}Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on');" + "\nport_label('input', 3, '^{B}v_o', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmode', 'on');\nport_labe" + "l('input', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('input', 6, '^{B}g', 'texmode', 'on');\nport_label('output" + "', 1, '\\Theta_{filtered}', 'texmode', 'on');\nport_label('output', 2, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_" + "label('output', 3, '^{E}r_o', 'texmode', 'on');\ndisp('Sensors', 'texmode', 'on'); " } System { - Name "\n\n\n\n\n\n" + Name " Sensors " Location [-8, -8, 1928, 1048] Open off ModelBrowserVisibility off @@ -1053,65 +1173,79 @@ Model { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "150" + ZoomFactor "50" Block { BlockType Inport - Name "Rotor 0 Duty Cycle" - SID "542" - Position [-225, 303, -195, 317] - ZOrder -1 + Name "B_Omega" + SID "651" + Position [635, 568, 665, 582] + ZOrder 265 IconDisplay "Port number" } Block { BlockType Inport - Name "Rotor 1 Duty Cycle" - SID "543" - Position [-225, 363, -195, 377] - ZOrder 2 + Name "euler_angles" + SID "652" + Position [830, 1338, 860, 1352] + ZOrder 266 Port "2" IconDisplay "Port number" } Block { BlockType Inport - Name "Rotor 2 Duty Cycle" - SID "544" - Position [-225, 423, -195, 437] - ZOrder 1 + Name "B_vo" + SID "653" + Position [635, 503, 665, 517] + ZOrder 267 Port "3" IconDisplay "Port number" } Block { BlockType Inport - Name "Rotor 3 Duty Cycle" - SID "545" - Position [-225, 483, -195, 497] - ZOrder 3 + Name "E_ro" + SID "654" + Position [985, 1313, 1015, 1327] + ZOrder 268 Port "4" IconDisplay "Port number" } + Block { + BlockType Inport + Name "B_vo_dot" + SID "655" + Position [635, 438, 665, 452] + ZOrder 269 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "B_g" + SID "656" + Position [635, 633, 665, 647] + ZOrder 273 + Port "6" + IconDisplay "Port number" + } Block { BlockType SubSystem - Name "\n" - SID "546" - Ports [2, 1] - Position [420, 280, 640, 520] - ZOrder 48 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on + Name "3D Graphical Simulation" + SID "698" + Ports [2] + Position [1265, 1425, 1415, 1485] + ZOrder 287 + Commented "on" RequestExecContextInheritance off - SFBlockType "MATLAB Function" Variant off Object { $PropName "MaskObject" - $ObjectID 24 + $ObjectID 25 $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Vb_{eff}', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', " - "'on');\nport_label('output', 1, '\\alpha', 'texmode', 'on');\ndisp('Motor System');\n" + Display "port_label('input',1,'r_{o}','texmode','on')\nport_label('input',2,'\\Theta','texmode','on')" } System { - Name "\n" - Location [223, 338, 826, 833] + Name "3D Graphical Simulation" + Location [-8, -8, 1928, 1048] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -1124,419 +1258,492 @@ Model { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "33" Block { BlockType Inport - Name "Vb_eff" - SID "546::1" - Position [20, 101, 40, 119] + Name "Displacement" + SID "699" + Position [110, 218, 140, 232] ZOrder -1 IconDisplay "Port number" } Block { BlockType Inport - Name "angular_velocity" - SID "546::24" - Position [20, 136, 40, 154] - ZOrder 15 + Name "Euler Angles" + SID "700" + Position [125, 108, 155, 122] + ZOrder -2 Port "2" IconDisplay "Port number" } Block { - BlockType Demux - Name " Demux " - SID "546::32" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 17 - Outputs "1" + BlockType BusCreator + Name "Bus\nCreator" + SID "701" + Ports [3, 1] + Position [600, 76, 610, 154] + ZOrder -3 + ShowName off + Inputs "3" + DisplayOption "bar" + InheritFromInputs on } Block { - BlockType S-Function - Name " SFunction " - SID "546::31" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 5" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 16 - FunctionName "sf_sfun" - Parameters "If,Jreq,Kd,Kq,Kv,Rm" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on + BlockType BusCreator + Name "Bus\nCreator1" + SID "702" + Ports [3, 1] + Position [630, 191, 640, 269] + ZOrder -4 + ShowName off + Inputs "3" + DisplayOption "bar" + InheritFromInputs on + } + Block { + BlockType BusCreator + Name "Bus\nCreator2" + SID "703" + Ports [3, 1] + Position [385, 75, 390, 155] + ZOrder -5 + ShowName off + Inputs "3" + DisplayOption "bar" + InheritFromInputs on + } + Block { + BlockType BusSelector + Name "Bus\nSelector" + SID "704" + Ports [1, 3] + Position [500, 77, 505, 153] + ZOrder -6 + ShowName off + OutputSignals "phi,theta,psi" + Port { + PortNumber 1 + Name "<phi>" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } Port { PortNumber 2 - Name "angular_acceleration" + Name "<theta>" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "<psi>" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } } Block { - BlockType Terminator - Name " Terminator " - SID "546::33" - Position [460, 241, 480, 259] - ZOrder 18 + BlockType Demux + Name "Demux" + SID "705" + Ports [1, 3] + Position [440, 183, 450, 267] + ZOrder -7 + BackgroundColor "black" + ShowName off + Outputs "3" + DisplayOption "bar" } Block { - BlockType Outport - Name "angular_acceleration" - SID "546::23" - Position [460, 101, 480, 119] - ZOrder 14 - IconDisplay "Port number" + BlockType Demux + Name "Demux1" + SID "706" + Ports [1, 3] + Position [290, 75, 295, 155] + ZOrder -8 + ShowName off + Outputs "3" + DisplayOption "bar" + Port { + PortNumber 1 + Name "phi" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "theta" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "psi" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } } - Line { - ZOrder 1 - SrcBlock "Vb_eff" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " + Block { + BlockType Gain + Name "Gain" + SID "707" + Position [550, 240, 580, 270] + ZOrder -10 + Gain "-1" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain1" + SID "708" + Position [670, 208, 710, 252] + ZOrder -11 + Gain "eye(3)*1" + Multiplication "Matrix(K*u)" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain2" + SID "709" + Position [550, 190, 580, 220] + ZOrder -12 + Gain "-1" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType SubSystem + Name "MATLAB Function" + SID "710" + Ports [1, 1] + Position [655, 92, 725, 138] + ZOrder 5 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + System { + Name "MATLAB Function" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "21" + Block { + BlockType Inport + Name "u" + SID "710::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "710::20" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 11 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "710::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 11" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 10 + FunctionName "sf_sfun" + PortCounts "[1 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "y" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "710::21" + Position [460, 241, 480, 259] + ZOrder 12 + } + Block { + BlockType Outport + Name "y" + SID "710::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "u" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "y" + ZOrder 2 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "y" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType RateTransition + Name "Rate Transition" + SID "711" + Position [755, 94, 795, 136] + ZOrder -13 + NamePlacement "alternate" + OutPortSampleTime "0.06" + } + Block { + BlockType RateTransition + Name "Rate Transition1" + SID "712" + Position [735, 210, 770, 250] + ZOrder -14 + OutPortSampleTime "0.06" + } + Block { + BlockType Reference + Name "VR Sink" + SID "713" + Ports [2] + Position [865, 76, 1055, 234] + ZOrder -15 + LibraryVersion "1.36" + SourceBlock "vrlib/VR Sink" + SourceType "Virtual Reality Sink" + InstantiateOnLoad on + SampleTime "-1" + ViewEnable on + RemoteChange off + RemoteView off + FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" + WorldFileName "quadrotor_world_ucart.wrl" + AutoView on + VideoDimensions "[]" + AllowVariableSize off + } + Line { + ZOrder 1 + SrcBlock "Displacement" + SrcPort 1 + DstBlock "Demux" DstPort 1 } Line { ZOrder 2 - SrcBlock "angular_velocity" + SrcBlock "Bus\nCreator2" SrcPort 1 - DstBlock " SFunction " - DstPort 2 + DstBlock "Bus\nSelector" + DstPort 1 } Line { - Name "angular_acceleration" ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "angular_acceleration" - DstPort 1 + SrcBlock "Demux" + SrcPort 1 + Points [40, 0; 0, 40; 120, 0] + DstBlock "Bus\nCreator1" + DstPort 3 } Line { ZOrder 4 - SrcBlock " Demux " + SrcBlock "Gain" SrcPort 1 - DstBlock " Terminator " - DstPort 1 + Points [5, 0; 0, -25] + DstBlock "Bus\nCreator1" + DstPort 2 } Line { ZOrder 5 - SrcBlock " SFunction " + SrcBlock "Gain2" SrcPort 1 - DstBlock " Demux " + DstBlock "Bus\nCreator1" DstPort 1 } - } - } - Block { - BlockType SubSystem - Name "\n\n" - SID "547" - Ports [4, 1] - Position [55, 282, 290, 518] - ZOrder 36 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 25 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Rotor 0 Duty Cycle', 'texmode', 'on');\nport_label('input', 2, 'Rotor 1 Dut" - "y Cycle', 'texmode', 'on');\nport_label('input', 3, 'Rotor 2 Duty Cycle', 'texmode', 'on');\nport_label('input', " - "4, 'Rotor 3 Duty Cycle', 'texmode', 'on');\nport_label('output', 1, 'Vb_{eff}', 'texmode', 'on');\ndisp('ESC Syst" - "em');" - } - System { - Name "\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "37" - Block { - BlockType Inport - Name "rotor_0_duty_cycle" - SID "547::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "rotor_1_duty_cycle" - SID "547::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" + Line { + ZOrder 6 + SrcBlock "Rate Transition1" + SrcPort 1 + Points [35, 0; 0, -35] + DstBlock "VR Sink" + DstPort 2 } - Block { - BlockType Inport - Name "rotor_2_duty_cycle" - SID "547::23" - Position [20, 171, 40, 189] - ZOrder 14 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "rotor_3_duty_cycle" - SID "547::24" - Position [20, 206, 40, 224] - ZOrder 15 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "547::36" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 17 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "547::35" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 4" - Ports [4, 2] - Position [180, 102, 230, 203] - ZOrder 16 - FunctionName "sf_sfun" - Parameters "Pmax,Pmin,Vb" - PortCounts "[4 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "Vb_eff" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "547::37" - Position [460, 241, 480, 259] - ZOrder 18 + Line { + ZOrder 7 + SrcBlock "Rate Transition" + SrcPort 1 + DstBlock "VR Sink" + DstPort 1 } - Block { - BlockType Outport - Name "Vb_eff" - SID "547::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" + Line { + ZOrder 8 + SrcBlock "Demux" + SrcPort 3 + DstBlock "Gain" + DstPort 1 } Line { - ZOrder 1 - SrcBlock "rotor_0_duty_cycle" - SrcPort 1 - DstBlock " SFunction " + ZOrder 9 + SrcBlock "Demux" + SrcPort 2 + Points [80, 0] + DstBlock "Gain2" DstPort 1 } Line { - ZOrder 2 - SrcBlock "rotor_1_duty_cycle" + ZOrder 10 + SrcBlock "Bus\nCreator1" SrcPort 1 - DstBlock " SFunction " - DstPort 2 + DstBlock "Gain1" + DstPort 1 } Line { - ZOrder 3 - SrcBlock "rotor_2_duty_cycle" + Name "<phi>" + ZOrder 11 + Labels [0, 0] + SrcBlock "Bus\nSelector" SrcPort 1 - DstBlock " SFunction " + Points [0, -10; 45, 0; 0, 60] + DstBlock "Bus\nCreator" DstPort 3 } Line { - ZOrder 4 - SrcBlock "rotor_3_duty_cycle" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 + Name "<psi>" + ZOrder 12 + Labels [0, 0] + SrcBlock "Bus\nSelector" + SrcPort 3 + Points [0, -10; 75, 0] + DstBlock "Bus\nCreator" + DstPort 2 } Line { - Name "Vb_eff" - ZOrder 5 + Name "<theta>" + ZOrder 13 Labels [0, 0] - SrcBlock " SFunction " + SrcBlock "Bus\nSelector" SrcPort 2 - DstBlock "Vb_eff" + Points [30, 0; 0, -25] + DstBlock "Bus\nCreator" DstPort 1 } Line { - ZOrder 6 - SrcBlock " Demux " + ZOrder 14 + SrcBlock "Gain1" SrcPort 1 - DstBlock " Terminator " + DstBlock "Rate Transition1" DstPort 1 } Line { - ZOrder 7 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "\n\n\n\n" - SID "548" - Ports [0, 1] - Position [335, 664, 485, 786] - ZOrder 96 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 26 - $ClassName "Simulink.Mask" - Display "port_label('output', 1, '^EF_g', 'texmode', 'on');\nfprintf('Gravity');\n" - } - System { - Name "\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "30" - Block { - BlockType Demux - Name " Demux " - SID "548::28" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 19 - Outputs "1" - } - Block { - BlockType Ground - Name " Ground " - SID "548::30" - Position [20, 121, 40, 139] - ZOrder 21 - } - Block { - BlockType S-Function - Name " SFunction " - SID "548::27" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 1" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 18 - FunctionName "sf_sfun" - Parameters "g,m" - PortCounts "[1 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "E_Fg" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "548::29" - Position [460, 241, 480, 259] - ZOrder 20 - } - Block { - BlockType Outport - Name "E_Fg" - SID "548::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" + Name "psi" + ZOrder 15 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 3 + DstBlock "Bus\nCreator2" + DstPort 3 } Line { - Name "E_Fg" - ZOrder 1 + Name "theta" + ZOrder 16 Labels [0, 0] - SrcBlock " SFunction " + SrcBlock "Demux1" SrcPort 2 - DstBlock "E_Fg" + DstBlock "Bus\nCreator2" + DstPort 2 + } + Line { + Name "phi" + ZOrder 17 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 1 + DstBlock "Bus\nCreator2" DstPort 1 } Line { - ZOrder 2 - SrcBlock " Ground " + ZOrder 18 + SrcBlock "Euler Angles" SrcPort 1 - DstBlock " SFunction " + DstBlock "Demux1" DstPort 1 } Line { - ZOrder 3 - SrcBlock " Demux " + ZOrder 19 + SrcBlock "Bus\nCreator" SrcPort 1 - DstBlock " Terminator " + DstBlock "MATLAB Function" DstPort 1 } Line { - ZOrder 4 - SrcBlock " SFunction " + ZOrder 20 + SrcBlock "MATLAB Function" SrcPort 1 - DstBlock " Demux " + DstBlock "Rate Transition" DstPort 1 } } } Block { BlockType SubSystem - Name "\n\n\n\n\n\n\n" - SID "549" - Ports [2, 1] - Position [1395, 499, 1630, 706] - ZOrder 75 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on + Name "3D Graphical Simulation1" + SID "714" + Ports [2] + Position [1900, 1435, 2050, 1495] + ZOrder 290 + Commented "on" RequestExecContextInheritance off - SFBlockType "MATLAB Function" Variant off Object { $PropName "MaskObject" - $ObjectID 27 + $ObjectID 26 $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^Bv_o', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" - "');\nport_label('output', 1, '^Er_o', 'texmode', 'on');\ndisp('L_{EB}', 'texmode', 'on');" + Display "port_label('input',1, '\\Theta','texmode','on')\nport_label('input',2,'r_{o}','texmode','on')" } System { - Name "\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] + Name "3D Graphical Simulation1" + Location [-8, -8, 1928, 1048] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -1549,366 +1756,523 @@ Model { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "31" Block { BlockType Inport - Name "B_vo" - SID "549::24" - Position [20, 101, 40, 119] - ZOrder 15 + Name "Euler Angles\n" + SID "715" + Position [180, 108, 210, 122] + ZOrder -1 IconDisplay "Port number" } Block { BlockType Inport - Name "euler_angles" - SID "549::28" - Position [20, 136, 40, 154] - ZOrder 19 + Name "Displacement" + SID "716" + Position [180, 218, 210, 232] + ZOrder -2 Port "2" IconDisplay "Port number" } Block { - BlockType Demux - Name " Demux " - SID "549::30" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 21 - Outputs "1" + BlockType BusCreator + Name "Bus\nCreator" + SID "717" + Ports [3, 1] + Position [600, 76, 610, 154] + ZOrder -3 + ShowName off + Inputs "3" + DisplayOption "bar" + InheritFromInputs on } Block { - BlockType S-Function - Name " SFunction " - SID "549::29" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 2" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 20 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on + BlockType BusCreator + Name "Bus\nCreator1" + SID "718" + Ports [3, 1] + Position [630, 191, 640, 269] + ZOrder -4 + ShowName off + Inputs "3" + DisplayOption "bar" + InheritFromInputs on + } + Block { + BlockType BusCreator + Name "Bus\nCreator2" + SID "719" + Ports [3, 1] + Position [385, 75, 390, 155] + ZOrder -5 + ShowName off + Inputs "3" + DisplayOption "bar" + InheritFromInputs on + } + Block { + BlockType BusSelector + Name "Bus\nSelector" + SID "720" + Ports [1, 3] + Position [500, 77, 505, 153] + ZOrder -6 + ShowName off + OutputSignals "phi,theta,psi" + Port { + PortNumber 1 + Name "<phi>" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } Port { PortNumber 2 - Name "E_ro" + Name "<theta>" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "<psi>" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } - } - Block { - BlockType Terminator - Name " Terminator " - SID "549::31" - Position [460, 241, 480, 259] - ZOrder 22 - } - Block { - BlockType Outport - Name "E_ro" - SID "549::26" - Position [460, 101, 480, 119] - ZOrder 17 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "B_vo" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "E_ro" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "E_ro" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "\n\n\n\n\n\n\n\n" - SID "550" - Ports [5, 2] - Position [950, 281, 1150, 519] - ZOrder 52 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 28 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '\\alpha', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', '" - "on');\nport_label('input', 3, '^BF_g', 'texmode', 'on');\nport_label('input', 4, '^B\\Omega', 'texmode', 'on');\n" - "port_label('input', 5, '^Bv_o', 'texmode', 'on');\nport_label('output', 1, '^Bd\\Omega/dt', 'texmode', 'on');\npo" - "rt_label('output', 2, '^Bdv_o/dt', 'texmode', 'on');\ndisp('Rotor System', 'texmode', 'on');" - } - System { - Name "\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "50" - Block { - BlockType Inport - Name "angular_acceleration" - SID "550::27" - Position [20, 101, 40, 119] - ZOrder 18 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "angular_velocity" - SID "550::28" - Position [20, 136, 40, 154] - ZOrder 19 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Fg" - SID "550::47" - Position [20, 171, 40, 189] - ZOrder 20 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_omega" - SID "550::25" - Position [20, 206, 40, 224] - ZOrder 16 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "550::24" - Position [20, 246, 40, 264] - ZOrder 15 - Port "5" - IconDisplay "Port number" } Block { BlockType Demux - Name " Demux " - SID "550::49" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 22 - Outputs "1" + Name "Demux" + SID "721" + Ports [1, 3] + Position [440, 183, 450, 267] + ZOrder -7 + BackgroundColor "black" + ShowName off + Outputs "3" + DisplayOption "bar" } Block { - BlockType S-Function - Name " SFunction " - SID "550::48" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 6" - Ports [5, 3] - Position [180, 100, 230, 220] - ZOrder 21 - FunctionName "sf_sfun" - Parameters "Jreq,Jxx,Jyy,Jzz,Kd,Kt,m,rhx,rhy,rhz" - PortCounts "[5 3]" - SFunctionDeploymentMode off - EnableBusSupport on + BlockType Demux + Name "Demux1" + SID "722" + Ports [1, 3] + Position [290, 75, 295, 155] + ZOrder -8 + ShowName off + Outputs "3" + DisplayOption "bar" + Port { + PortNumber 1 + Name "phi" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } Port { PortNumber 2 - Name "B_omega_dot" + Name "theta" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } Port { PortNumber 3 - Name "B_vo_dot" + Name "psi" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } } Block { - BlockType Terminator - Name " Terminator " - SID "550::50" - Position [460, 241, 480, 259] - ZOrder 23 + BlockType Gain + Name "Gain" + SID "723" + Position [550, 240, 580, 270] + ZOrder -10 + Gain "-1" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Outport - Name "B_omega_dot" - SID "550::22" - Position [460, 101, 480, 119] - ZOrder 13 - IconDisplay "Port number" + BlockType Gain + Name "Gain1" + SID "724" + Position [670, 208, 710, 252] + ZOrder -11 + Gain "eye(3)*1" + Multiplication "Matrix(K*u)" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Outport - Name "B_vo_dot" - SID "550::5" - Position [460, 136, 480, 154] - ZOrder -5 - Port "2" - IconDisplay "Port number" + BlockType Gain + Name "Gain2" + SID "725" + Position [550, 190, 580, 220] + ZOrder -12 + Gain "-1" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType SubSystem + Name "MATLAB Function" + SID "726" + Ports [1, 1] + Position [655, 92, 725, 138] + ZOrder 5 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + System { + Name "MATLAB Function" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "21" + Block { + BlockType Inport + Name "u" + SID "726::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "726::20" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 11 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "726::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 3" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 10 + FunctionName "sf_sfun" + PortCounts "[1 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "y" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "726::21" + Position [460, 241, 480, 259] + ZOrder 12 + } + Block { + BlockType Outport + Name "y" + SID "726::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "u" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "y" + ZOrder 2 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "y" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType RateTransition + Name "Rate Transition" + SID "727" + Position [755, 94, 795, 136] + ZOrder -13 + NamePlacement "alternate" + OutPortSampleTime "0.06" + } + Block { + BlockType RateTransition + Name "Rate Transition1" + SID "728" + Position [745, 210, 780, 250] + ZOrder -14 + OutPortSampleTime "0.06" + } + Block { + BlockType Reference + Name "VR Sink" + SID "729" + Ports [2] + Position [865, 76, 1055, 234] + ZOrder -15 + LibraryVersion "1.36" + SourceBlock "vrlib/VR Sink" + SourceType "Virtual Reality Sink" + InstantiateOnLoad on + SampleTime "-1" + ViewEnable on + RemoteChange off + RemoteView off + FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" + WorldFileName "quadrotor_world_ucart.wrl" + AutoView on + VideoDimensions "[]" + AllowVariableSize off } Line { ZOrder 1 - SrcBlock "angular_acceleration" + SrcBlock "Bus\nCreator2" SrcPort 1 - DstBlock " SFunction " + DstBlock "Bus\nSelector" DstPort 1 } Line { ZOrder 2 - SrcBlock "angular_velocity" + SrcBlock "Demux" SrcPort 1 - DstBlock " SFunction " - DstPort 2 + Points [40, 0; 0, 40; 120, 0] + DstBlock "Bus\nCreator1" + DstPort 3 } Line { ZOrder 3 - SrcBlock "B_Fg" + SrcBlock "Gain" SrcPort 1 - DstBlock " SFunction " - DstPort 3 + Points [5, 0; 0, -25] + DstBlock "Bus\nCreator1" + DstPort 2 } Line { ZOrder 4 - SrcBlock "B_omega" + SrcBlock "Gain2" SrcPort 1 - DstBlock " SFunction " - DstPort 4 + DstBlock "Bus\nCreator1" + DstPort 1 } Line { ZOrder 5 - SrcBlock "B_vo" + SrcBlock "Rate Transition1" SrcPort 1 - DstBlock " SFunction " - DstPort 5 + Points [25, 0; 0, -35] + DstBlock "VR Sink" + DstPort 2 } Line { - Name "B_omega_dot" ZOrder 6 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "B_omega_dot" + SrcBlock "Rate Transition" + SrcPort 1 + DstBlock "VR Sink" DstPort 1 } Line { - Name "B_vo_dot" ZOrder 7 - Labels [0, 0] - SrcBlock " SFunction " + SrcBlock "Demux" SrcPort 3 - DstBlock "B_vo_dot" + DstBlock "Gain" DstPort 1 } Line { ZOrder 8 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " + SrcBlock "Demux" + SrcPort 2 + Points [80, 0] + DstBlock "Gain2" DstPort 1 } Line { ZOrder 9 - SrcBlock " SFunction " + SrcBlock "Bus\nCreator1" SrcPort 1 - Points [20, 0] - DstBlock " Demux " + DstBlock "Gain1" DstPort 1 } - } - } - Block { - BlockType SubSystem - Name "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SID "551" - Ports [2, 1] - Position [1395, 303, 1630, 452] - ZOrder 81 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 29 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^B\\Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode'," - " 'on');\nport_label('output', 1, 'd\\Theta/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode', 'on');" - } - System { - Name "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" + Line { + Name "<phi>" + ZOrder 10 + Labels [0, 0] + SrcBlock "Bus\nSelector" + SrcPort 1 + Points [0, -10; 45, 0; 0, 60] + DstBlock "Bus\nCreator" + DstPort 3 + } + Line { + Name "<psi>" + ZOrder 11 + Labels [0, 0] + SrcBlock "Bus\nSelector" + SrcPort 3 + Points [0, -10; 75, 0] + DstBlock "Bus\nCreator" + DstPort 2 + } + Line { + Name "<theta>" + ZOrder 12 + Labels [0, 0] + SrcBlock "Bus\nSelector" + SrcPort 2 + Points [30, 0; 0, -25] + DstBlock "Bus\nCreator" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "Rate Transition1" + DstPort 1 + } + Line { + Name "psi" + ZOrder 14 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 3 + DstBlock "Bus\nCreator2" + DstPort 3 + } + Line { + Name "theta" + ZOrder 15 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 2 + DstBlock "Bus\nCreator2" + DstPort 2 + } + Line { + Name "phi" + ZOrder 16 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 1 + DstBlock "Bus\nCreator2" + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock "Bus\nCreator" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "MATLAB Function" + SrcPort 1 + DstBlock "Rate Transition" + DstPort 1 + } + Line { + ZOrder 19 + SrcBlock "Displacement" + SrcPort 1 + DstBlock "Demux" + DstPort 1 + } + Line { + ZOrder 20 + SrcBlock "Euler Angles\n" + SrcPort 1 + DstBlock "Demux1" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Aeb\n\n\n\n\n\n\n\n\n\n" + SID "679" + Ports [2, 1] + Position [1475, 579, 1655, 701] + ZOrder 275 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 27 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU" + "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode'," + " 'on');" + } + System { + Name "Aeb\n\n\n\n\n\n\n\n\n\n" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" SIDHighWatermark "25" Block { BlockType Inport - Name "B_omega" - SID "551::1" + Name "gyro_reading" + SID "679::1" Position [20, 101, 40, 119] ZOrder -1 IconDisplay "Port number" } Block { BlockType Inport - Name "euler_angles" - SID "551::22" + Name "euler_angles_filtered" + SID "679::22" Position [20, 136, 40, 154] ZOrder 13 Port "2" @@ -1917,7 +2281,7 @@ Model { Block { BlockType Demux Name " Demux " - SID "551::24" + SID "679::24" Ports [1, 1] Position [270, 230, 320, 270] ZOrder 15 @@ -1926,8 +2290,8 @@ Model { Block { BlockType S-Function Name " SFunction " - SID "551::23" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 7" + SID "679::23" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 12" Ports [2, 2] Position [180, 100, 230, 160] ZOrder 14 @@ -1937,7 +2301,7 @@ Model { EnableBusSupport on Port { PortNumber 2 - Name "euler_rates" + Name "euler_rates_IMU" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } @@ -1945,21 +2309,21 @@ Model { Block { BlockType Terminator Name " Terminator " - SID "551::25" + SID "679::25" Position [460, 241, 480, 259] ZOrder 16 } Block { BlockType Outport - Name "euler_rates" - SID "551::5" + Name "euler_rates_IMU" + SID "679::5" Position [460, 101, 480, 119] ZOrder -5 IconDisplay "Port number" } Line { ZOrder 1 - SrcBlock "B_omega" + SrcBlock "gyro_reading" SrcPort 1 Points [120, 0] DstBlock " SFunction " @@ -1967,18 +2331,18 @@ Model { } Line { ZOrder 2 - SrcBlock "euler_angles" + SrcBlock "euler_angles_filtered" SrcPort 1 DstBlock " SFunction " DstPort 2 } Line { - Name "euler_rates" + Name "euler_rates_IMU" ZOrder 3 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 - DstBlock "euler_rates" + DstBlock "euler_rates_IMU" DstPort 1 } Line { @@ -1999,11 +2363,12 @@ Model { } Block { BlockType SubSystem - Name "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SID "552" - Ports [2, 2] - Position [600, 694, 770, 816] - ZOrder 97 + Name "Aeb_c\n\n\n\n\n\n\n\n\n\n1" + SID "1335" + Ports [2, 1] + Position [1460, 969, 1640, 1091] + ZOrder 322 + ShowName off ErrorFcn "Stateflow.Translate.translate" PermitHierarchicalResolution "ParametersOnly" TreatAsAtomicUnit on @@ -2012,13 +2377,14 @@ Model { Variant off Object { $PropName "MaskObject" - $ObjectID 30 + $ObjectID 28 $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^EF_g', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" - "');\nport_label('output', 1, '^BF_g', 'texmode', 'on');\ndisp('L_{BE}', 'texmode', 'on');" + Display "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU" + "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode'," + " 'on');" } System { - Name "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + Name "Aeb_c\n\n\n\n\n\n\n\n\n\n1" Location [223, 338, 826, 833] Open off ModelBrowserVisibility off @@ -2032,55 +2398,48 @@ Model { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "33" + SIDHighWatermark "25" Block { BlockType Inport - Name "E_Fg" - SID "552::24" + Name "gyro_reading" + SID "1335::1" Position [20, 101, 40, 119] - ZOrder 15 + ZOrder -1 IconDisplay "Port number" } Block { BlockType Inport - Name "euler_angles" - SID "552::28" + Name "euler_angles_filtered" + SID "1335::22" Position [20, 136, 40, 154] - ZOrder 19 + ZOrder 13 Port "2" IconDisplay "Port number" } Block { BlockType Demux Name " Demux " - SID "552::30" + SID "1335::24" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 21 + ZOrder 15 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "552::29" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 8" - Ports [2, 3] - Position [180, 100, 230, 180] - ZOrder 20 + SID "1335::23" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 16" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 14 FunctionName "sf_sfun" - Parameters "m" - PortCounts "[2 3]" + PortCounts "[2 2]" SFunctionDeploymentMode off EnableBusSupport on Port { PortNumber 2 - Name "B_Fg" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "B_g" + Name "euler_rates_IMU" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } @@ -2088,68 +2447,51 @@ Model { Block { BlockType Terminator Name " Terminator " - SID "552::31" + SID "1335::25" Position [460, 241, 480, 259] - ZOrder 22 + ZOrder 16 } Block { BlockType Outport - Name "B_Fg" - SID "552::26" + Name "euler_rates_IMU" + SID "1335::5" Position [460, 101, 480, 119] - ZOrder 17 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_g" - SID "552::32" - Position [460, 136, 480, 154] - ZOrder 23 - Port "2" + ZOrder -5 IconDisplay "Port number" } Line { - ZOrder 19 - SrcBlock "E_Fg" + ZOrder 1 + SrcBlock "gyro_reading" SrcPort 1 + Points [120, 0] DstBlock " SFunction " DstPort 1 } Line { - ZOrder 20 - SrcBlock "euler_angles" + ZOrder 2 + SrcBlock "euler_angles_filtered" SrcPort 1 DstBlock " SFunction " DstPort 2 } Line { - Name "B_Fg" - ZOrder 21 + Name "euler_rates_IMU" + ZOrder 3 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 - DstBlock "B_Fg" - DstPort 1 - } - Line { - Name "B_g" - ZOrder 22 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "B_g" + DstBlock "euler_rates_IMU" DstPort 1 } Line { - ZOrder 23 + ZOrder 4 SrcBlock " Demux " SrcPort 1 DstBlock " Terminator " DstPort 1 } Line { - ZOrder 24 + ZOrder 5 SrcBlock " SFunction " SrcPort 1 DstBlock " Demux " @@ -2158,1467 +2500,1307 @@ Model { } } Block { - BlockType Demux - Name "Demux" - SID "934" - Ports [1, 4] - Position [-60, 321, -55, 454] - ZOrder 105 - ShowName off - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "954" - Ports [1, 3] - Position [1830, 526, 1835, 574] - ZOrder 107 + BlockType SubSystem + Name "Calculate Pitch and Roll" + SID "680" + Ports [2, 2] + Position [1485, 379, 1655, 521] + ZOrder 284 ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "x position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 29 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, 'Accelerometer Reading', 'texmode', 'on');\nport_label('input', 2, '\\phi_{a" + "ccel}', 'texmode', 'on');\nport_label('output', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('output', 2, " + "'\\phi_{accel}', 'texmode', 'on');\ndisp('Calculate Pitch and Roll', 'texmode', 'on');" } - Port { - PortNumber 2 - Name "y position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "z position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux2" - SID "955" - Ports [1, 3] - Position [1830, 301, 1835, 349] - ZOrder 109 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Roll" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Pitch" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Yaw" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux3" - SID "957" - Ports [1, 3] - Position [1830, 406, 1835, 454] - ZOrder 117 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body x velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body y velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body z velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux4" - SID "959" - Ports [1, 3] - Position [1830, 161, 1835, 209] - ZOrder 115 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body roll velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body pitch velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body yaw velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" + System { + Name "Calculate Pitch and Roll" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "26" + Block { + BlockType Inport + Name "accel_reading" + SID "680::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "accel_roll_prev" + SID "680::23" + Position [20, 136, 40, 154] + ZOrder 14 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "680::20" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 11 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "680::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 13" + Ports [2, 3] + Position [180, 105, 230, 185] + ZOrder 10 + FunctionName "sf_sfun" + PortCounts "[2 3]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "accel_pitch" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "accel_roll" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "680::21" + Position [460, 241, 480, 259] + ZOrder 12 + } + Block { + BlockType Outport + Name "accel_pitch" + SID "680::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "accel_roll" + SID "680::22" + Position [460, 136, 480, 154] + ZOrder 13 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "accel_reading" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "accel_roll_prev" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "accel_pitch" + ZOrder 3 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "accel_pitch" + DstPort 1 + } + Line { + Name "accel_roll" + ZOrder 4 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "accel_roll" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } } } Block { - BlockType Demux - Name "Demux5" - SID "961" - Ports [1, 3] - Position [1830, 641, 1835, 689] - ZOrder 119 + BlockType SubSystem + Name "Complimentary Filter" + SID "1339" + Ports [4, 1] + Position [1880, 372, 2065, 713] + ZOrder 326 + ForegroundColor "red" ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body x acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body y acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 30 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('input', 2, '\\phi_{accel}'" + ", 'texmode', 'on');\nport_label('input', 3, '\\Theta_{Gyro}', 'texmode', 'on');\n%port_label('input', 4, '\\Theta" + "_{IMU}', 'texmode', 'on');\nport_label('output', 1, '\\Theta_{IMU}', 'texmode', 'on');\ndisp('Complementary Filte" + "r', 'texmode', 'on');" } - Port { - PortNumber 3 - Name "Body z acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" + System { + Name "Complimentary Filter" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "35" + Block { + BlockType Inport + Name "accel_pitch" + SID "1339::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "accel_roll" + SID "1339::29" + Position [20, 136, 40, 154] + ZOrder 20 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "euler_rates_gyro" + SID "1339::22" + Position [20, 171, 40, 189] + ZOrder 13 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "prev_euler_angles" + SID "1339::35" + Position [20, 206, 40, 224] + ZOrder 21 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "1339::20" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 11 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "1339::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 19" + Ports [4, 2] + Position [180, 147, 230, 248] + ZOrder 10 + FunctionName "sf_sfun" + PortCounts "[4 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "euler_angles_IMU" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "1339::21" + Position [460, 241, 480, 259] + ZOrder 12 + } + Block { + BlockType Outport + Name "euler_angles_IMU" + SID "1339::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 7 + SrcBlock "accel_pitch" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "accel_roll" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 9 + SrcBlock "euler_rates_gyro" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 10 + SrcBlock "prev_euler_angles" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 4 + } + Line { + Name "euler_angles_IMU" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "euler_angles_IMU" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } } } Block { - BlockType Integrator - Name "Integrator" - SID "553" + BlockType Delay + Name "Delay" + SID "1341" Ports [1, 1] - Position [730, 340, 760, 370] - ZOrder 49 + Position [1955, 728, 1990, 762] + ZOrder 328 + BlockMirror on + InputPortMap "u0" + DelayLength "1" + InitialCondition "0" } Block { - BlockType Integrator - Name "Integrator1" - SID "554" + BlockType Delay + Name "Delay1" + SID "731" Ports [1, 1] - Position [1225, 445, 1255, 475] - ZOrder 53 + Position [1555, 528, 1590, 562] + ZOrder 285 + BlockMirror on + ForegroundColor "red" + InputPortMap "u0" + DelayLength "1" + InitialCondition "0" + SampleTime "Tq" } Block { - BlockType Integrator - Name "Integrator2" - SID "555" + BlockType Delay + Name "Delay2" + SID "772" Ports [1, 1] - Position [1225, 325, 1255, 355] - ZOrder 54 + Position [695, 428, 730, 462] + ZOrder 304 + InputPortMap "u0" + DelayLength "1" + InitialCondition "0" + SampleTime "Tq" } Block { - BlockType Integrator - Name "Integrator3" - SID "556" - Ports [1, 1] - Position [1685, 590, 1715, 620] - ZOrder 98 + BlockType Demux + Name "Demux" + SID "1344" + Ports [1, 3] + Position [920, 1313, 925, 1377] + ZOrder 329 + ShowName off + Outputs "3" + DisplayOption "bar" } Block { - BlockType Integrator - Name "Integrator4" - SID "557" + BlockType Demux + Name "Demux1" + SID "1404" + Ports [1, 2] + Position [2285, 726, 2290, 764] + ZOrder 347 + ShowName off + Outputs "2" + DisplayOption "bar" + } + Block { + BlockType Demux + Name "Demux2" + SID "1405" + Ports [1, 2] + Position [2285, 916, 2290, 954] + ZOrder 348 + ShowName off + Outputs "2" + DisplayOption "bar" + } + Block { + BlockType Reference + Name "First-Order\nHold" + SID "734" Ports [1, 1] - Position [1685, 365, 1715, 395] - ZOrder 77 - ContinuousStateAttributes "['phi' 'theta' 'psi']" + Position [1790, 1435, 1825, 1465] + ZOrder 292 + ForegroundColor "yellow" + LibraryVersion "1.388" + DisableCoverage on + SourceBlock "simulink/Discrete/First-Order\nHold" + SourceType "First-Order Hold" + ContentPreviewEnabled off + Ts "5e-3" } Block { - BlockType Scope - Name "Scope" - SID "558" - Ports [1] - Position [350, 279, 380, 311] - ZOrder 46 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData - YMin 10.94391 - YMax 11.11734 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] + BlockType Reference + Name "First-Order\nHold1" + SID "735" + Ports [1, 1] + Position [1790, 1530, 1825, 1560] + ZOrder 296 + ForegroundColor "yellow" + LibraryVersion "1.388" + DisableCoverage on + SourceBlock "simulink/Discrete/First-Order\nHold" + SourceType "First-Order Hold" + ContentPreviewEnabled off + Ts "5e-3" } Block { - BlockType Scope - Name "Scope1" - SID "559" - Ports [1] - Position [740, 229, 770, 261] - ZOrder 50 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -1469.49513 - YMax 13225.4562 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope10" - SID "956" - Ports [3] - Position [1935, 303, 1975, 347] - ZOrder 108 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -1.00000~-1.00000~-1.00000 - YMax 1.00000~1.00000~1.00000 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [643 335 1366 766] - } - Block { - BlockType Scope - Name "Scope11" - SID "960" - Ports [3] - Position [1935, 163, 1975, 207] - ZOrder 114 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -1.00000~-1.00000~-1.00000 - YMax 1.00000~1.00000~1.00000 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [643 335 1366 766] - } - Block { - BlockType Scope - Name "Scope2" - SID "560" - Ports [1] - Position [890, 229, 920, 261] - ZOrder 51 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -100.77485 - YMax 906.97366 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope3" - SID "958" - Ports [3] - Position [1935, 408, 1975, 452] - ZOrder 116 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -1.00000~-71.40595~-81.80792 - YMax 1.00000~93.1255~67.47699 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope4" - SID "962" - Ports [3] - Position [1935, 643, 1975, 687] - ZOrder 118 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData4 - YMin -1019.9483~-1019.9483~-1019.9483 - YMax 1049.2638~1049.2638~1049.2638 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope6" - SID "564" - Ports [3] - Position [1935, 528, 1975, 572] - ZOrder 79 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData4 - YMin -1.00000~-1.00000~-980.09781 - YMax 1.00000~1.00000~109.0196 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" + BlockType SubSystem + Name "IMU\n\n\n\n\n\n" + SID "658" + Ports [4, 2] + Position [765, 410, 960, 675] + ZOrder 272 + ShowName off + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 31 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode'" + ", 'on')\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')" + "\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_label('output', 2, 'Gyroscope Reading'," + " 'texmode', 'on')\ndisp('IMU', 'texmode', 'on');" } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [643 335 1366 766] - } - Block { - BlockType Scope - Name "Scope7" - SID "565" - Ports [1] - Position [535, 644, 565, 676] - ZOrder 99 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -1.45924 - YMax 13.13314 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope8" - SID "566" - Ports [1] - Position [820, 629, 850, 661] - ZOrder 100 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -14.59237 - YMax 14.59237 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope9" - SID "567" - Ports [1] - Position [1225, 229, 1255, 261] - ZOrder 102 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -0.0198 - YMax 0.17819 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1909 1039] - } - Block { - BlockType Step - Name "Step" - SID "935" - Position [-150, 375, -120, 405] - ZOrder 106 - Before "68.25*ones(4,1)" - After "[ 68.25; 69.25; 69.25; 68.25 ]" - SampleTime "0" - } - Block { - BlockType Outport - Name "B_omega" - SID "568" - Position [1815, 238, 1845, 252] - ZOrder 61 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "euler_angles" - SID "569" - Position [1815, 373, 1845, 387] - ZOrder 91 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo" - SID "570" - Position [1815, 468, 1845, 482] - ZOrder 58 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "E_ro" - SID "571" - Position [1830, 598, 1860, 612] - ZOrder 88 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo_dot" - SID "572" - Position [1830, 718, 1860, 732] - ZOrder 103 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_g" - SID "573" - Position [1830, 778, 1860, 792] - ZOrder 104 - Port "6" - IconDisplay "Port number" - } - Line { - ZOrder 5 - SrcBlock "\n\n" - SrcPort 1 - Points [23, 0; 0, -59] - Branch { - ZOrder 6 - Points [2, 0; 0, -46] - DstBlock "Scope" - DstPort 1 - } - Branch { - ZOrder 7 - Points [0, -1] - DstBlock "\n" - DstPort 1 - } - } - Line { - ZOrder 8 - SrcBlock "\n" - SrcPort 1 - Points [40, 0; 0, -45] - Branch { - ZOrder 9 - DstBlock "Integrator" - DstPort 1 - } - Branch { - ZOrder 10 - Points [0, -45] - Branch { - ZOrder 11 - Points [0, -65] - DstBlock "Scope1" - DstPort 1 + System { + Name "IMU\n\n\n\n\n\n" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "B_vo_dot" + SID "659" + Position [110, 173, 140, 187] + ZOrder 17 + IconDisplay "Port number" } - Branch { - ZOrder 12 - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 1 + Block { + BlockType Inport + Name "B_vo" + SID "660" + Position [110, 208, 140, 222] + ZOrder 25 + Port "2" + IconDisplay "Port number" } - } - } - Line { - ZOrder 13 - SrcBlock "Integrator" - SrcPort 1 - Points [8, 0] - Branch { - ZOrder 14 - Points [60, 0] - Branch { - ZOrder 15 - Points [0, -110] - DstBlock "Scope2" - DstPort 1 + Block { + BlockType Inport + Name "B_Omega" + SID "661" + Position [110, 243, 140, 257] + ZOrder 26 + Port "3" + IconDisplay "Port number" } - Branch { - ZOrder 16 - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 2 + Block { + BlockType Inport + Name "B_g" + SID "662" + Position [110, 278, 140, 292] + ZOrder 27 + Port "4" + IconDisplay "Port number" } - } - Branch { - ZOrder 17 - Points [0, 210; -396, 0; 0, -105] - DstBlock "\n" - DstPort 2 - } - } - Line { - ZOrder 18 - SrcBlock "\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [34, 0] - Branch { - ZOrder 19 - Points [0, -95] - DstBlock "Scope9" - DstPort 1 - } - Branch { - ZOrder 20 - DstBlock "Integrator2" - DstPort 1 - } - } - Line { - ZOrder 21 - SrcBlock "\n\n\n\n\n\n\n\n" - SrcPort 2 - Points [32, 0] - Branch { - ZOrder 22 - Points [0, 265; 600, 0] - Branch { - ZOrder 199 - Points [0, -60] - DstBlock "Demux5" - DstPort 1 + Block { + BlockType SubSystem + Name "\n\n\n\n\n\n\n" + SID "663" + Ports [5, 2] + Position [250, 165, 445, 335] + ZOrder 1 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 32 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode', 'on'" + ")\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')\nport_la" + "bel('input', 5, 'r_{oc}', 'texmode', 'on')\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_" + "label('output', 2, 'Gyroscope Reading', 'texmode', 'on')\ndisp('Ideal IMU', 'texmode', 'on');" + } + System { + Name "\n\n\n\n\n\n\n" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "31" + Block { + BlockType Inport + Name "B_vo_dot" + SID "663::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "B_vo" + SID "663::22" + Position [20, 136, 40, 154] + ZOrder 13 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "B_Omega" + SID "663::19" + Position [20, 171, 40, 189] + ZOrder 10 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "B_g" + SID "663::20" + Position [20, 206, 40, 224] + ZOrder 11 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "r_oc" + SID "663::23" + Position [20, 246, 40, 264] + ZOrder 14 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "663::25" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 16 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "663::24" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 10" + Ports [5, 3] + Position [180, 110, 230, 230] + ZOrder 15 + FunctionName "sf_sfun" + Parameters "g" + PortCounts "[5 3]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "accelReading" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "gyroReading" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "663::26" + Position [460, 241, 480, 259] + ZOrder 17 + } + Block { + BlockType Outport + Name "accelReading" + SID "663::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "gyroReading" + SID "663::21" + Position [460, 136, 480, 154] + ZOrder 12 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "B_vo_dot" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "B_vo" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 3 + SrcBlock "B_Omega" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 4 + SrcBlock "B_g" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + ZOrder 5 + SrcBlock "r_oc" + SrcPort 1 + DstBlock " SFunction " + DstPort 5 + } + Line { + Name "accelReading" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "accelReading" + DstPort 1 + } + Line { + Name "gyroReading" + ZOrder 7 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "gyroReading" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } } - Branch { - ZOrder 198 - DstBlock "B_vo_dot" - DstPort 1 + Block { + BlockType Delay + Name "Delay" + SID "1371" + Ports [1, 1] + Position [915, 193, 950, 227] + ZOrder 50 + Commented "through" + InputPortMap "u0" + DelayLength "4" + InitialCondition "0" + SampleTime "Tq" } - } - Branch { - ZOrder 23 - DstBlock "Integrator1" - DstPort 1 - } - } - Line { - ZOrder 24 - SrcBlock "Integrator2" - SrcPort 1 - Points [55, 0] - Branch { - ZOrder 25 - Points [0, -95; 454, 0] - Branch { - ZOrder 117 - DstBlock "B_omega" - DstPort 1 + Block { + BlockType Delay + Name "Delay1" + SID "1372" + Ports [1, 1] + Position [915, 278, 950, 312] + ZOrder 51 + Commented "through" + InputPortMap "u0" + DelayLength "4" + InitialCondition "0" + SampleTime "Tq" } - Branch { - ZOrder 115 - Points [0, -60] - DstBlock "Demux4" - DstPort 1 + Block { + BlockType DiscreteFilter + Name "Discrete Filter1" + SID "921" + Ports [1, 1] + Position [790, 192, 850, 228] + ZOrder 48 + InputPortMap "u0" + Numerator "[0 0.1454]" + Denominator "[1 -0.8546]" + InitialStates "[0, 0, -1]" + SampleTime "Tq" } - } - Branch { - ZOrder 28 - Points [0, 226; -422, 0; 0, -121] - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 4 - } - Branch { - ZOrder 29 - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - Line { - ZOrder 37 - SrcBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Integrator4" - DstPort 1 - } - Line { - ZOrder 47 - SrcBlock "\n\n\n\n" - SrcPort 1 - Points [7, 0] - Branch { - ZOrder 64 - Points [0, -65] - DstBlock "Scope7" - DstPort 1 - } - Branch { - ZOrder 49 - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - Line { - ZOrder 50 - SrcBlock "\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Integrator3" - DstPort 1 - } - Line { - ZOrder 51 - SrcBlock "Integrator3" - SrcPort 1 - Points [64, 0] - Branch { - ZOrder 88 - Points [0, -55] - DstBlock "Demux1" - DstPort 1 - } - Branch { - ZOrder 87 - DstBlock "E_ro" - DstPort 1 - } - } - Line { - ZOrder 54 - SrcBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [24, 0; 0, -30] - Branch { - ZOrder 55 - Points [0, -50] - DstBlock "Scope8" - DstPort 1 - } - Branch { - ZOrder 56 - Points [74, 0; 0, -295] - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 3 - } - } - Line { - ZOrder 61 - SrcBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 2 - DstBlock "B_g" - DstPort 1 - } - Line { - ZOrder 71 - SrcBlock "Demux" - SrcPort 1 - Points [50, 0; 0, -25] - DstBlock "\n\n" - DstPort 1 - } - Line { - ZOrder 72 - SrcBlock "Demux" - SrcPort 2 - DstBlock "\n\n" - DstPort 2 - } - Line { - ZOrder 73 - SrcBlock "Demux" - SrcPort 3 - Points [50, 0; 0, 25] - DstBlock "\n\n" - DstPort 3 - } - Line { - ZOrder 74 - SrcBlock "Demux" - SrcPort 4 - Points [50, 0; 0, 50] - DstBlock "\n\n" - DstPort 4 - } - Line { - ZOrder 70 - SrcBlock "Step" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - Name "y position" - ZOrder 89 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Scope6" - DstPort 2 - } - Line { - Name "x position" - ZOrder 90 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Scope6" - DstPort 1 - } - Line { - Name "z position" - ZOrder 91 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Scope6" - DstPort 3 - } - Line { - ZOrder 38 - SrcBlock "Integrator4" - SrcPort 1 - Points [20, 0] - Branch { - ZOrder 39 - Points [30, 0] - Branch { - ZOrder 97 - Points [0, -55] - DstBlock "Demux2" - DstPort 1 + Block { + BlockType DiscreteFilter + Name "Discrete Filter2" + SID "922" + Ports [1, 1] + Position [790, 277, 850, 313] + ZOrder 49 + InputPortMap "u0" + Numerator "[0 0.1454]" + Denominator "[1 -0.8546]" + SampleTime "Tq" } - Branch { - ZOrder 96 - DstBlock "euler_angles" - DstPort 1 + Block { + BlockType DiscreteIntegrator + Name "Discrete-Time\nIntegrator" + SID "835" + Ports [1, 1] + Position [765, 407, 800, 443] + ZOrder 30 + InitialConditionSetting "State (most efficient)" + SampleTime "-1" + ICPrevOutput "DiscIntNeverNeededParam" + ICPrevScaledInput "DiscIntNeverNeededParam" } - } - Branch { - ZOrder 42 - Points [0, 460; -385, 0] - Branch { - ZOrder 65 - Points [0, -185] - Branch { - ZOrder 44 - DstBlock "\n\n\n\n\n\n\n" - DstPort 2 + Block { + BlockType DiscreteIntegrator + Name "Discrete-Time\nIntegrator2" + SID "839" + Ports [1, 1] + Position [595, 407, 630, 443] + ZOrder 34 + InitialConditionSetting "State (most efficient)" + SampleTime "-1" + ICPrevOutput "DiscIntNeverNeededParam" + ICPrevScaledInput "DiscIntNeverNeededParam" + } + Block { + BlockType Ground + Name "Ground" + SID "664" + Position [605, 340, 625, 360] + ZOrder 23 + } + Block { + BlockType Ground + Name "Ground1" + SID "665" + Position [605, 145, 625, 165] + ZOrder 24 + } + Block { + BlockType Integrator + Name "Integrator" + SID "844" + Ports [1, 1] + Position [240, 360, 270, 390] + ZOrder 39 + } + Block { + BlockType Scope + Name "Scope" + SID "836" + Ports [1] + Position [845, 409, 875, 441] + ZOrder 31 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -0.0001 + YMax 0.00021 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" } - Branch { - ZOrder 45 - Points [0, -240] - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 2 + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" } + Location [680 330 1240 750] } - Branch { - ZOrder 46 - Points [-787, 0; 0, -55] - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 2 + Block { + BlockType Scope + Name "Scope2" + SID "840" + Ports [1] + Position [670, 409, 700, 441] + ZOrder 35 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData3 + YMin -1.00000 + YMax 1.00000 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [680 330 1240 750] } - } - } - Line { - Name "Pitch" - ZOrder 93 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 2 - DstBlock "Scope10" - DstPort 2 - } - Line { - Name "Roll" - ZOrder 94 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 1 - DstBlock "Scope10" - DstPort 1 - } - Line { - Name "Yaw" - ZOrder 95 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 3 - DstBlock "Scope10" - DstPort 3 - } - Line { - Name "Body pitch velocity" - ZOrder 111 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 2 - DstBlock "Scope11" - DstPort 2 - } - Line { - Name "Body roll velocity" - ZOrder 112 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 1 - DstBlock "Scope11" - DstPort 1 - } - Line { - Name "Body yaw velocity" - ZOrder 113 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 3 - DstBlock "Scope11" - DstPort 3 - } - Line { - Name "Body y velocity" - ZOrder 118 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 2 - DstBlock "Scope3" - DstPort 2 - } - Line { - Name "Body x velocity" - ZOrder 119 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 1 - DstBlock "Scope3" - DstPort 1 - } - Line { - Name "Body z velocity" - ZOrder 120 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 3 - DstBlock "Scope3" - DstPort 3 - } - Line { - Name "Body y acceleration" - ZOrder 124 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 2 - DstBlock "Scope4" - DstPort 2 - } - Line { - Name "Body x acceleration" - ZOrder 125 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 1 - DstBlock "Scope4" - DstPort 1 - } - Line { - Name "Body z acceleration" - ZOrder 126 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 3 - DstBlock "Scope4" - DstPort 3 - } - Line { - ZOrder 30 - SrcBlock "Integrator1" - SrcPort 1 - Points [34, 0; 0, 90] - Branch { - ZOrder 195 - Points [-383, 0; 0, -60] - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 5 - } - Branch { - ZOrder 194 - Points [76, 0] - Branch { - ZOrder 196 - DstBlock "\n\n\n\n\n\n\n" - DstPort 1 - } - Branch { - ZOrder 192 - Points [0, -75; 401, 0] - Branch { - ZOrder 201 - Points [0, -45] - DstBlock "Demux3" - DstPort 1 + Block { + BlockType Scope + Name "Scope5" + SID "845" + Ports [1] + Position [295, 359, 325, 391] + ZOrder 40 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData6 + YMin -1.00000 + YMax 1.00000 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" } - Branch { - ZOrder 200 - DstBlock "B_vo" - DstPort 1 + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" } + Location [306 114 866 534] } - } - } - } - } - Block { - BlockType SubSystem - Name " " - SID "601" - Ports [6, 3] - Position [1445, 477, 1665, 713] - ZOrder 68 - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 31 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on');" - "\nport_label('input', 3, '^{B}v_o', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmode', 'on');\nport_labe" - "l('input', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('input', 6, '^{B}g', 'texmode', 'on');\nport_label('output" - "', 1, 'Euler Angles Filtered', 'texmode', 'on');\nport_label('output', 2, 'Euler Rates', 'texmode', 'on');\nport_labe" - "l('output', 3, 'Current Position', 'texmode', 'on');\ndisp('Sensors', 'texmode', 'on'); " - } - System { - Name " " - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "80" - Block { - BlockType Inport - Name "B_Omega" - SID "863" - Position [1015, 678, 1045, 692] - ZOrder 265 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "864" - Position [1720, 1043, 1750, 1057] - ZOrder 266 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "865" - Position [1015, 613, 1045, 627] - ZOrder 267 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "E_ro" - SID "866" - Position [1720, 963, 1750, 977] - ZOrder 268 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo_dot" - SID "867" - Position [1015, 548, 1045, 562] - ZOrder 269 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "868" - Position [1015, 743, 1045, 757] - ZOrder 273 - Port "6" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "\n\n\n\n\n\n\n\n" - SID "869" - Ports [4, 1] - Position [2025, 483, 2210, 782] - ZOrder 274 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 32 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('input', 2, '\\phi_{accel}'" - ", 'texmode', 'on');\nport_label('input', 3, 'd\\Theta_{IMU}/dt', 'texmode', 'on');\nport_label('input', 4, '\\The" - "ta_{IMU}', 'texmode', 'on');\nport_label('output', 1, '\\Theta_{IMU}', 'texmode', 'on');\ndisp('Complimentary Fil" - "ter', 'texmode', 'on');" - } - System { - Name "\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "32" Block { - BlockType Inport - Name "accel_pitch" - SID "869::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" + BlockType Sum + Name "Sum" + SID "666" + Ports [2, 1] + Position [715, 285, 735, 305] + ZOrder 7 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Inport - Name "accel_roll" - SID "869::29" - Position [20, 136, 40, 154] - ZOrder 20 - Port "2" - IconDisplay "Port number" + BlockType Sum + Name "Sum1" + SID "667" + Ports [2, 1] + Position [715, 200, 735, 220] + ZOrder 8 + ShowName off + IconShape "round" + Inputs "++|" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Inport - Name "euler_angles_gyro" - SID "869::22" - Position [20, 171, 40, 189] - ZOrder 13 - Port "3" - IconDisplay "Port number" + BlockType Sum + Name "Sum2" + SID "668" + Ports [2, 1] + Position [625, 285, 645, 305] + ZOrder 11 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Inport - Name "prev_euler_angles_IMU" - SID "869::28" - Position [20, 206, 40, 224] - ZOrder 19 - Port "4" - IconDisplay "Port number" + BlockType Sum + Name "Sum3" + SID "669" + Ports [2, 1] + Position [625, 200, 645, 220] + ZOrder 12 + ShowName off + IconShape "round" + Inputs "++|" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Demux - Name " Demux " - SID "869::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" + BlockType RandomNumber + Name "accelerometer_noise" + SID "670" + Position [655, 105, 685, 135] + ZOrder 2 + Mean "zeros(3,1)" + Variance "[ 3e-7 ; 3.3e-7 ; 7.2e-7 ] " + Seed "[0,1,2]" + SampleTime "Tq" } Block { - BlockType S-Function - Name " SFunction " - SID "869::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 9" - Ports [4, 2] - Position [180, 132, 230, 233] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[4 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_angles_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } + BlockType Quantizer + Name "accelerometer_quantizer" + SID "671" + Position [1030, 195, 1060, 225] + ZOrder 9 + ForegroundColor "red" + QuantizationInterval "2.4400e-04" } Block { - BlockType Terminator - Name " Terminator " - SID "869::21" - Position [460, 241, 480, 259] - ZOrder 12 + BlockType ZeroOrderHold + Name "accelerometer_sampling" + SID "672" + Position [510, 195, 545, 225] + ZOrder 15 + SampleTime "Tq" } Block { - BlockType Outport - Name "euler_angles_IMU" - SID "869::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" + BlockType RandomNumber + Name "gyroscope_noise" + SID "673" + Position [655, 335, 685, 365] + ZOrder 6 + Mean "zeros(3,1)" + Variance "[ 2.2e-8 ; 1.1e-7 ; 2.4e-8 ]" + Seed "[0,1,2]" + SampleTime "Tq" } - Line { - ZOrder 1 - SrcBlock "accel_pitch" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 + Block { + BlockType Quantizer + Name "gyroscope_qunatizer" + SID "674" + Position [1030, 280, 1060, 310] + ZOrder 10 + ForegroundColor "red" + QuantizationInterval "1.1e-3" } - Line { - ZOrder 2 - SrcBlock "accel_roll" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 + Block { + BlockType ZeroOrderHold + Name "gyroscope_sampling" + SID "675" + Position [510, 280, 545, 310] + ZOrder 16 + SampleTime "Tq" + } + Block { + BlockType Constant + Name "r_oc" + SID "676" + Position [30, 307, 95, 333] + ZOrder 28 + Value "zeros(3,1)" + } + Block { + BlockType Outport + Name "accelerometer" + SID "677" + Position [1135, 203, 1165, 217] + ZOrder 29 + ForegroundColor "red" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "gyroscope" + SID "678" + Position [1135, 288, 1165, 302] + ZOrder 21 + ForegroundColor "red" + Port "2" + IconDisplay "Port number" } Line { ZOrder 3 - SrcBlock "euler_angles_gyro" + SrcBlock "accelerometer_noise" SrcPort 1 - DstBlock " SFunction " - DstPort 3 + Points [35, 0] + DstBlock "Sum1" + DstPort 1 } Line { - ZOrder 4 - SrcBlock "prev_euler_angles_IMU" + ZOrder 5 + SrcBlock "Sum2" SrcPort 1 - DstBlock " SFunction " + DstBlock "Sum" + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock "Sum3" + SrcPort 1 + DstBlock "Sum1" + DstPort 2 + } + Line { + ZOrder 8 + SrcBlock "gyroscope_noise" + SrcPort 1 + Points [35, 0] + Branch { + ZOrder 87 + DstBlock "Sum" + DstPort 2 + } + Branch { + ZOrder 35 + Points [0, 75] + DstBlock "Discrete-Time\nIntegrator" + DstPort 1 + } + } + Line { + ZOrder 11 + SrcBlock "gyroscope_sampling" + SrcPort 1 + Points [30, 0] + Branch { + ZOrder 85 + DstBlock "Sum2" + DstPort 1 + } + Branch { + ZOrder 45 + DstBlock "Discrete-Time\nIntegrator2" + DstPort 1 + } + } + Line { + ZOrder 12 + SrcBlock "accelerometer_sampling" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + ZOrder 13 + SrcBlock "Ground" + SrcPort 1 + Points [5, 0] + DstBlock "Sum2" + DstPort 2 + } + Line { + ZOrder 14 + SrcBlock "Ground1" + SrcPort 1 + Points [5, 0] + DstBlock "Sum3" + DstPort 1 + } + Line { + ZOrder 15 + SrcBlock "B_vo_dot" + SrcPort 1 + DstBlock "\n\n\n\n\n\n\n" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock "B_vo" + SrcPort 1 + DstBlock "\n\n\n\n\n\n\n" + DstPort 2 + } + Line { + ZOrder 17 + SrcBlock "B_Omega" + SrcPort 1 + Points [48, 0] + Branch { + ZOrder 50 + Points [0, 125] + DstBlock "Integrator" + DstPort 1 + } + Branch { + ZOrder 49 + DstBlock "\n\n\n\n\n\n\n" + DstPort 3 + } + } + Line { + ZOrder 18 + SrcBlock "B_g" + SrcPort 1 + DstBlock "\n\n\n\n\n\n\n" DstPort 4 } Line { - Name "euler_angles_IMU" - ZOrder 5 - Labels [0, 0] - SrcBlock " SFunction " + ZOrder 19 + SrcBlock "r_oc" + SrcPort 1 + DstBlock "\n\n\n\n\n\n\n" + DstPort 5 + } + Line { + ZOrder 30 + SrcBlock "\n\n\n\n\n\n\n" SrcPort 2 - DstBlock "euler_angles_IMU" + DstBlock "gyroscope_sampling" DstPort 1 } Line { - ZOrder 6 - SrcBlock " Demux " + ZOrder 31 + SrcBlock "\n\n\n\n\n\n\n" SrcPort 1 - DstBlock " Terminator " + DstBlock "accelerometer_sampling" DstPort 1 } Line { - ZOrder 7 - SrcBlock " SFunction " + ZOrder 36 + SrcBlock "Discrete-Time\nIntegrator" SrcPort 1 - DstBlock " Demux " + DstBlock "Scope" + DstPort 1 + } + Line { + ZOrder 40 + SrcBlock "Discrete-Time\nIntegrator2" + SrcPort 1 + DstBlock "Scope2" + DstPort 1 + } + Line { + ZOrder 48 + SrcBlock "Integrator" + SrcPort 1 + DstBlock "Scope5" + DstPort 1 + } + Line { + ZOrder 124 + SrcBlock "Sum1" + SrcPort 1 + DstBlock "Discrete Filter1" + DstPort 1 + } + Line { + ZOrder 126 + SrcBlock "Sum" + SrcPort 1 + DstBlock "Discrete Filter2" + DstPort 1 + } + Line { + ZOrder 128 + SrcBlock "accelerometer_quantizer" + SrcPort 1 + DstBlock "accelerometer" + DstPort 1 + } + Line { + ZOrder 130 + SrcBlock "gyroscope_qunatizer" + SrcPort 1 + DstBlock "gyroscope" + DstPort 1 + } + Line { + ZOrder 127 + SrcBlock "Discrete Filter1" + SrcPort 1 + DstBlock "Delay" + DstPort 1 + } + Line { + ZOrder 129 + SrcBlock "Discrete Filter2" + SrcPort 1 + DstBlock "Delay1" + DstPort 1 + } + Line { + ZOrder 133 + SrcBlock "Delay" + SrcPort 1 + DstBlock "accelerometer_quantizer" + DstPort 1 + } + Line { + ZOrder 134 + SrcBlock "Delay1" + SrcPort 1 + DstBlock "gyroscope_qunatizer" DstPort 1 } } } Block { BlockType SubSystem - Name "\n\n\n\n\n\n\n\n\n\n" - SID "870" - Ports [4, 2] - Position [1145, 520, 1340, 785] - ZOrder 272 + Name "MATLAB Function" + SID "1389" + Ports [3, 1] + Position [1885, 897, 2075, 1113] + ZOrder 343 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on RequestExecContextInheritance off + SFBlockType "MATLAB Function" Variant off - Object { - $PropName "MaskObject" - $ObjectID 33 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode'" - ", 'on')\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')" - "\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_label('output', 2, 'Gyroscope Reading'," - " 'texmode', 'on')\ndisp('IMU', 'texmode', 'on');" - } System { - Name "\n\n\n\n\n\n\n\n\n\n" - Location [-8, -8, 1928, 1048] + Name "MATLAB Function" + Location [223, 338, 826, 833] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -3631,564 +3813,4221 @@ Model { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" + SIDHighWatermark "23" Block { BlockType Inport - Name "B_vo_dot" - SID "871" - Position [110, 173, 140, 187] - ZOrder 17 + Name "accel_pitch" + SID "1389::1" + Position [20, 101, 40, 119] + ZOrder -1 IconDisplay "Port number" } Block { BlockType Inport - Name "B_vo" - SID "872" - Position [110, 208, 140, 222] - ZOrder 25 + Name "accel_roll" + SID "1389::22" + Position [20, 136, 40, 154] + ZOrder 13 Port "2" IconDisplay "Port number" } Block { BlockType Inport - Name "B_Omega" - SID "873" - Position [110, 243, 140, 257] - ZOrder 26 + Name "euler_rates_gyro" + SID "1389::23" + Position [20, 171, 40, 189] + ZOrder 14 Port "3" IconDisplay "Port number" } Block { - BlockType Inport - Name "B_g" - SID "874" - Position [110, 278, 140, 292] - ZOrder 27 - Port "4" - IconDisplay "Port number" + BlockType Demux + Name " Demux " + SID "1389::20" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 11 + Outputs "1" } Block { - BlockType SubSystem - Name "\n\n\n\n\n\n\n" - SID "875" - Ports [5, 2] - Position [250, 165, 445, 335] - ZOrder 1 - LibraryVersion "1.32" - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 34 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode', 'on'" - ")\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')\nport_la" - "bel('input', 5, 'r_{oc}', 'texmode', 'on')\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_" - "label('output', 2, 'Gyroscope Reading', 'texmode', 'on')\ndisp('Ideal IMU', 'texmode', 'on');" - } - System { - Name "\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "31" - Block { - BlockType Inport - Name "B_vo_dot" - SID "875::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "875::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Omega" - SID "875::19" - Position [20, 171, 40, 189] - ZOrder 10 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "875::20" - Position [20, 206, 40, 224] - ZOrder 11 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "r_oc" - SID "875::23" - Position [20, 246, 40, 264] - ZOrder 14 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "875::25" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 16 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "875::24" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 10" - Ports [5, 3] - Position [180, 110, 230, 230] - ZOrder 15 - FunctionName "sf_sfun" - Parameters "g" - PortCounts "[5 3]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "accelReading" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "gyroReading" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "875::26" - Position [460, 241, 480, 259] - ZOrder 17 - } - Block { - BlockType Outport - Name "accelReading" - SID "875::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "gyroReading" - SID "875::21" - Position [460, 136, 480, 154] - ZOrder 12 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 57 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 58 - SrcBlock "B_vo" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 59 - SrcBlock "B_Omega" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 60 - SrcBlock "B_g" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - ZOrder 61 - SrcBlock "r_oc" - SrcPort 1 - DstBlock " SFunction " - DstPort 5 - } - Line { - Name "accelReading" - ZOrder 62 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "accelReading" - DstPort 1 - } - Line { - Name "gyroReading" - ZOrder 63 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "gyroReading" - DstPort 1 - } - Line { - ZOrder 64 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 65 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } + BlockType S-Function + Name " SFunction " + SID "1389::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 17" + Ports [3, 2] + Position [180, 100, 230, 180] + ZOrder 10 + FunctionName "sf_sfun" + PortCounts "[3 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "euler_angles_IMU" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" } } Block { - BlockType Ground - Name "Ground" - SID "876" - Position [550, 340, 570, 360] - ZOrder 23 + BlockType Terminator + Name " Terminator " + SID "1389::21" + Position [460, 241, 480, 259] + ZOrder 12 } Block { - BlockType Ground - Name "Ground1" - SID "877" - Position [550, 145, 570, 165] - ZOrder 24 + BlockType Outport + Name "euler_angles_IMU" + SID "1389::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" } - Block { - BlockType Sum - Name "Sum" - SID "878" - Ports [2, 1] - Position [690, 285, 710, 305] - ZOrder 7 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + Line { + ZOrder 14 + SrcBlock "accel_pitch" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 } - Block { - BlockType Sum - Name "Sum1" - SID "879" - Ports [2, 1] - Position [690, 200, 710, 220] - ZOrder 8 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + Line { + ZOrder 15 + SrcBlock "accel_roll" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 } - Block { - BlockType Sum - Name "Sum2" - SID "880" - Ports [2, 1] - Position [570, 285, 590, 305] - ZOrder 11 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + Line { + ZOrder 16 + SrcBlock "euler_rates_gyro" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 } - Block { - BlockType Sum - Name "Sum3" - SID "881" - Ports [2, 1] - Position [570, 200, 590, 220] - ZOrder 12 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + Line { + Name "euler_angles_IMU" + ZOrder 17 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "euler_angles_IMU" + DstPort 1 } - Block { - BlockType RandomNumber - Name "accelerometer_noise" - SID "882" - Position [630, 140, 660, 170] - ZOrder 2 - Mean "zeros(3,1)" - Variance "[ 3e-7 ; 3.3e-7 ; 7.2e-7 ] " - Seed "[0,1,2]" - SampleTime "6.1e-3" + Line { + ZOrder 18 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 } - Block { - BlockType Quantizer - Name "accelerometer_quantizer" - SID "883" - Position [770, 195, 800, 225] - ZOrder 9 - QuantizationInterval "2.4400e-04" + Line { + ZOrder 19 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 } + } + } + Block { + BlockType SubSystem + Name "MATLAB Function1" + SID "1407" + Ports [1, 2] + Position [1520, 196, 1625, 329] + ZOrder 350 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + System { + Name "MATLAB Function1" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "22" Block { - BlockType ZeroOrderHold - Name "accelerometer_sampling" - SID "884" - Position [495, 195, 530, 225] - ZOrder 15 - SampleTime "6.1e-3" + BlockType Inport + Name "accel_reading" + SID "1407::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" } Block { - BlockType RandomNumber - Name "gyroscope_noise" - SID "885" - Position [630, 315, 660, 345] - ZOrder 6 - Mean "zeros(3,1)" - Variance "[ 2.2e-8 ; 1.1e-7 ; 2.4e-8 ]" - Seed "[0,1,2]" - SampleTime "6.1e-3" + BlockType Demux + Name " Demux " + SID "1407::20" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 11 + Outputs "1" } Block { - BlockType Quantizer - Name "gyroscope_qunatizer" - SID "886" - Position [770, 280, 800, 310] + BlockType S-Function + Name " SFunction " + SID "1407::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 18" + Ports [1, 3] + Position [180, 100, 230, 180] ZOrder 10 - QuantizationInterval "1.1e-3" - } - Block { - BlockType ZeroOrderHold - Name "gyroscope_sampling" - SID "887" - Position [495, 280, 530, 310] - ZOrder 16 - SampleTime "6.1e-3" + FunctionName "sf_sfun" + PortCounts "[1 3]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "accel_pitch" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "accel_roll" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } } Block { - BlockType Constant - Name "r_oc" - SID "888" - Position [30, 307, 95, 333] - ZOrder 28 - Value "zeros(3,1)" + BlockType Terminator + Name " Terminator " + SID "1407::21" + Position [460, 241, 480, 259] + ZOrder 12 } Block { BlockType Outport - Name "accelerometer" - SID "889" - Position [885, 203, 915, 217] - ZOrder 29 + Name "accel_pitch" + SID "1407::5" + Position [460, 101, 480, 119] + ZOrder -5 IconDisplay "Port number" } Block { BlockType Outport - Name "gyroscope" - SID "890" - Position [885, 288, 915, 302] - ZOrder 21 + Name "accel_roll" + SID "1407::22" + Position [460, 136, 480, 154] + ZOrder 13 Port "2" IconDisplay "Port number" } Line { - ZOrder 1 - SrcBlock "gyroscope_qunatizer" + ZOrder 9 + SrcBlock "accel_reading" SrcPort 1 - DstBlock "gyroscope" + DstBlock " SFunction " DstPort 1 } Line { - ZOrder 2 - SrcBlock "accelerometer_quantizer" + Name "accel_pitch" + ZOrder 10 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "accel_pitch" + DstPort 1 + } + Line { + Name "accel_roll" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "accel_roll" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " Demux " SrcPort 1 - DstBlock "accelerometer" + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Mux + Name "Mux" + SID "1345" + Ports [2, 1] + Position [2180, 536, 2185, 574] + ZOrder 330 + ShowName off + Inputs "2" + DisplayOption "bar" + } + Block { + BlockType SubSystem + Name "OptiTrack Camera System\n\n " + SID "681" + Ports [2, 2] + Position [1255, 1296, 1495, 1389] + ZOrder 299 + ForegroundColor "yellow" + ShowName off + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 33 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '^{E}r_o', 'texmode', 'on');\nport_label('input', 2, '\\psi', 'texmode', 'on" + "');\nport_label('output', 1, '^{E}r_o camera', 'texmode', 'on');\nport_label('output', 2, '\\psi camera', 'texmod" + "e', 'on');\ndisp('OptiTrack Camera System', 'texmode', 'on');" + } + System { + Name "OptiTrack Camera System\n\n " + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "E_ro" + SID "682" + Position [295, 238, 325, 252] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "yaw" + SID "683" + Position [295, 338, 325, 352] + ZOrder 4 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType RandomNumber + Name "E_ro_noise" + SID "684" + Position [545, 175, 575, 205] + ZOrder 30 + Mean "zeros(3,1)" + Variance "[ 7.9664e-10 ; 1.1928e-10 ; 5.0636e-10 ] " + Seed "[0,1,2]" + SampleTime "Tc" + } + Block { + BlockType Quantizer + Name "E_ro_quantizer" + SID "685" + Position [685, 230, 715, 260] + ZOrder 34 + QuantizationInterval "2.4400e-04" + } + Block { + BlockType ZeroOrderHold + Name "E_ro_sampling" + SID "686" + Position [410, 230, 445, 260] + ZOrder 38 + SampleTime "Tc" + } + Block { + BlockType Ground + Name "Ground1" + SID "687" + Position [465, 180, 485, 200] + ZOrder 42 + } + Block { + BlockType Ground + Name "Ground2" + SID "688" + Position [465, 390, 485, 410] + ZOrder 56 + } + Block { + BlockType Sum + Name "Sum1" + SID "689" + Ports [2, 1] + Position [605, 235, 625, 255] + ZOrder 33 + ShowName off + IconShape "round" + Inputs "++|" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "690" + Ports [2, 1] + Position [485, 235, 505, 255] + ZOrder 37 + ShowName off + IconShape "round" + Inputs "++|" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum4" + SID "691" + Ports [2, 1] + Position [605, 335, 625, 355] + ZOrder 47 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum6" + SID "692" + Ports [2, 1] + Position [485, 335, 505, 355] + ZOrder 51 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType RandomNumber + Name "yaw_noise" + SID "693" + Position [545, 365, 575, 395] + ZOrder 46 + Variance "1.0783e-9" + SampleTime "Tc" + } + Block { + BlockType Quantizer + Name "yaw_quantizer" + SID "694" + Position [685, 330, 715, 360] + ZOrder 50 + QuantizationInterval "1.1e-3" + } + Block { + BlockType ZeroOrderHold + Name "yaw_sampling" + SID "695" + Position [410, 330, 445, 360] + ZOrder 54 + SampleTime "Tc" + } + Block { + BlockType Outport + Name "E_ro_camera" + SID "696" + Position [800, 238, 830, 252] + ZOrder 43 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "yaw_camera" + SID "697" + Position [800, 338, 830, 352] + ZOrder 55 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 2 + SrcBlock "E_ro_noise" + SrcPort 1 + Points [35, 0] + DstBlock "Sum1" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Sum3" + SrcPort 1 + DstBlock "Sum1" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "Sum1" + SrcPort 1 + DstBlock "E_ro_quantizer" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "E_ro_sampling" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + ZOrder 6 + SrcBlock "Ground1" + SrcPort 1 + Points [5, 0] + DstBlock "Sum3" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "yaw_quantizer" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock "Sum6" + SrcPort 1 + DstBlock "Sum4" + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "yaw_noise" + SrcPort 1 + Points [35, 0] + DstBlock "Sum4" + DstPort 2 + } + Line { + ZOrder 11 + SrcBlock "yaw_sampling" + SrcPort 1 + DstBlock "Sum6" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "Ground2" + SrcPort 1 + Points [5, 0] + DstBlock "Sum6" + DstPort 2 + } + Line { + ZOrder 17 + SrcBlock "yaw" + SrcPort 1 + DstBlock "yaw_sampling" + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "E_ro" + SrcPort 1 + DstBlock "E_ro_sampling" + DstPort 1 + } + Line { + ZOrder 19 + SrcBlock "E_ro_quantizer" + SrcPort 1 + DstBlock "E_ro_camera" + DstPort 1 + } + Line { + ZOrder 20 + SrcBlock "yaw_quantizer" + SrcPort 1 + DstBlock "yaw_camera" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Raw Accelerometer Data" + SID "1258" + Ports [1, 1] + Position [1030, 457, 1185, 503] + ZOrder 317 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 34 + $ClassName "Simulink.Mask" + Display "disp('Raw Accelerometer Data', 'texmode', 'on');" + } + System { + Name "Raw Accelerometer Data" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "175" + Block { + BlockType Inport + Name "raw_accel_model" + SID "1259" + Position [20, 128, 50, 142] + ZOrder 288 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1260" + Ports [1, 1] + Position [145, 155, 340, 185] + ZOrder 287 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 35 + $ClassName "Simulink.Mask" + Display "disp('Raw Accelerometer Data from Model', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "raw_accel_model" + SID "1261" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "raw_accel" + SID "1262" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "raw_accel_model" + SrcPort 1 + DstBlock "raw_accel" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Raw Accelerometer Data " + SID "1263" + Ports [0, 1] + Position [175, 75, 305, 105] + ZOrder 279 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 36 + $ClassName "Simulink.Mask" + Display "disp('Raw Accelerometer Data', 'texmode', 'on');" + } + System { + Name "Raw Accelerometer Data " + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType FromWorkspace + Name "From\nWorkspace5" + SID "1264" + Position [5, 18, 105, 42] + ZOrder 210 + VariableName "raw_accel_data" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "raw_accel" + SID "1265" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace5" + SrcPort 1 + DstBlock "raw_accel" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "raw_accel" + SID "1266" + Position [405, 128, 435, 142] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1267" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" + "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" + "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" + "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" + "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" + "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" + "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" + "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" + "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" + "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" + "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" + "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" + "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" + "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" + "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType SubSystem + Name "Raw Gyroscope Data" + SID "1268" + Ports [1, 1] + Position [1030, 587, 1185, 633] + ZOrder 318 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 37 + $ClassName "Simulink.Mask" + Display "disp('Raw Gyroscope Data', 'texmode', 'on');" + } + System { + Name "Raw Gyroscope Data" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "175" + Block { + BlockType Inport + Name "raw_gyro_model" + SID "1269" + Position [40, 128, 70, 142] + ZOrder 288 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1270" + Ports [1, 1] + Position [160, 153, 330, 187] + ZOrder 287 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 38 + $ClassName "Simulink.Mask" + Display "disp('Raw Gyroscope Data from Model', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [633, 0, 1286, 687] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "raw_gyro_model" + SID "1271" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "raw_gyro" + SID "1272" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "raw_gyro_model" + SrcPort 1 + DstBlock "raw_gyro" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Raw Gyroscope Data " + SID "1273" + Ports [0, 1] + Position [180, 77, 310, 113] + ZOrder 279 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 39 + $ClassName "Simulink.Mask" + Display "disp('Raw Gyroscope Data', 'texmode', 'on');" + } + System { + Name "Raw Gyroscope Data " + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType FromWorkspace + Name "From\nWorkspace5" + SID "1274" + Position [145, 53, 230, 77] + ZOrder 210 + VariableName "raw_accel_data" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "raw_gyro" + SID "1275" + Position [295, 58, 325, 72] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace5" + SrcPort 1 + DstBlock "raw_gyro" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "raw_gyro" + SID "1276" + Position [405, 128, 435, 142] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1277" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" + "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" + "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" + "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" + "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" + "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" + "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" + "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" + "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" + "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" + "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" + "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" + "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" + "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" + "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType ZeroOrderHold + Name "Sample" + SID "936" + Position [1640, 1305, 1675, 1335] + ZOrder 313 + ForegroundColor "green" + SampleTime "Tc" + } + Block { + BlockType ZeroOrderHold + Name "Sample1" + SID "937" + Position [1640, 1350, 1675, 1380] + ZOrder 314 + ForegroundColor "green" + SampleTime "Tc" + } + Block { + BlockType Scope + Name "Scope" + SID "737" + Ports [1] + Position [1315, 559, 1345, 591] + ZOrder 270 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -0.00277 + YMax 0.00209 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [680 330 1240 750] + } + Block { + BlockType Scope + Name "Scope1" + SID "738" + Ports [1] + Position [1315, 499, 1345, 531] + ZOrder 271 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData2 + YMin -2.04337 + YMax 0.22704 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1909 1039] + } + Block { + BlockType Scope + Name "Scope2" + SID "1386" + Ports [2] + Position [1810, 221, 1840, 254] + ZOrder 340 + NumInputPorts "2" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -1.867~-5 + YMax 1.68089~5 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope3" + SID "1387" + Ports [2] + Position [1810, 286, 1840, 319] + ZOrder 341 + NumInputPorts "2" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData2 + YMin -3.89902~-5 + YMax 3.92383~5 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1909 1039] + } + Block { + BlockType Scope + Name "Scope4" + SID "1388" + Ports [2] + Position [1720, 911, 1750, 944] + ZOrder 342 + NumInputPorts "2" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData3 + YMin -3.39538~-5 + YMax 1.81736~5 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope5" + SID "1403" + Ports [2] + Position [2525, 733, 2565, 782] + ZOrder 346 + NumInputPorts "2" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData4 + YMin -0.99149~-5 + YMax 0.86243~5 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope6" + SID "1406" + Ports [2] + Position [2525, 823, 2565, 872] + ZOrder 349 + NumInputPorts "2" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData5 + YMin -1.37391~-5 + YMax 0.98927~5 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType S-Function + Name "Soft Real Time" + SID "742" + Ports [] + Position [2008, 1540, 2095, 1571] + ZOrder 288 + ShowName off + Commented "on" + FunctionName "sfun_time" + Parameters "x" + SFunctionDeploymentMode off + EnableBusSupport off + Object { + $PropName "MaskObject" + $ObjectID 40 + $ClassName "Simulink.Mask" + Display "color('red')\ndisp('Soft Real Time')\n" + Object { + $PropName "Parameters" + $ObjectID 41 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "x" + Prompt "Time Scaling Factor" + Value "1" + } + } + } + Block { + BlockType ToWorkspace + Name "To Workspace4" + SID "1420" + Ports [1] + Position [1925, 1230, 2050, 1260] + ZOrder 351 + ShowName off + VariableName "position_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tc" + } + Block { + BlockType ToWorkspace + Name "To Workspace5" + SID "1256" + Ports [1] + Position [2360, 405, 2470, 435] + ZOrder 315 + ForegroundColor "red" + VariableName "angle_IMU_reading" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" + } + Block { + BlockType TransportDelay + Name "Transport\nDelay" + SID "933" + Ports [1, 1] + Position [1565, 1305, 1595, 1335] + ZOrder 310 + DelayTime "6e-3" + } + Block { + BlockType TransportDelay + Name "Transport\nDelay1" + SID "935" + Ports [1, 1] + Position [1565, 1350, 1595, 1380] + ZOrder 312 + DelayTime "6e-3" + } + Block { + BlockType Outport + Name "euler_angles_filtered" + SID "743" + Position [2245, 548, 2275, 562] + ZOrder 262 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "euler_rates" + SID "744" + Position [1255, 653, 1290, 667] + ZOrder 259 + ForegroundColor "red" + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "current_position" + SID "745" + Position [1925, 1313, 1955, 1327] + ZOrder 289 + Port "3" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "IMU\n\n\n\n\n\n" + SrcPort 1 + DstBlock "Raw Accelerometer Data" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "IMU\n\n\n\n\n\n" + SrcPort 2 + DstBlock "Raw Gyroscope Data" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "B_vo" + SrcPort 1 + DstBlock "IMU\n\n\n\n\n\n" + DstPort 2 + } + Line { + ZOrder 9 + SrcBlock "B_Omega" + SrcPort 1 + DstBlock "IMU\n\n\n\n\n\n" + DstPort 3 + } + Line { + ZOrder 10 + SrcBlock "B_g" + SrcPort 1 + DstBlock "IMU\n\n\n\n\n\n" + DstPort 4 + } + Line { + ZOrder 11 + SrcBlock "Calculate Pitch and Roll" + SrcPort 2 + Points [102, 0] + Branch { + ZOrder 553 + Points [0, -175] + DstBlock "Scope3" + DstPort 2 + } + Branch { + ZOrder 548 + Points [0, 60] + DstBlock "Delay1" + DstPort 1 + } + Branch { + ZOrder 245 + Points [76, 0] + Branch { + ZOrder 597 + Points [0, 520] + DstBlock "MATLAB Function" + DstPort 2 + } + Branch { + ZOrder 596 + Points [27, 0] + DstBlock "Complimentary Filter" + DstPort 2 + } + } + } + Line { + ZOrder 16 + SrcBlock "Calculate Pitch and Roll" + SrcPort 1 + Points [25, 0] + Branch { + ZOrder 552 + Points [0, -170] + DstBlock "Scope2" + DstPort 2 + } + Branch { + ZOrder 551 + Points [173, 0] + Branch { + ZOrder 595 + Points [0, 520] + DstBlock "MATLAB Function" + DstPort 1 + } + Branch { + ZOrder 594 + DstBlock "Complimentary Filter" + DstPort 1 + } + } + } + Line { + ZOrder 25 + SrcBlock "Delay1" + SrcPort 1 + Points [-89, 0; 0, -60] + DstBlock "Calculate Pitch and Roll" + DstPort 2 + } + Line { + ZOrder 33 + SrcBlock "First-Order\nHold" + SrcPort 1 + DstBlock "3D Graphical Simulation1" + DstPort 1 + } + Line { + ZOrder 34 + SrcBlock "E_ro" + SrcPort 1 + Points [191, 0] + Branch { + ZOrder 35 + Points [0, 120] + DstBlock "3D Graphical Simulation" + DstPort 1 + } + Branch { + ZOrder 36 + DstBlock "OptiTrack Camera System\n\n " + DstPort 1 + } + } + Line { + ZOrder 38 + SrcBlock "First-Order\nHold1" + SrcPort 1 + Points [20, 0; 0, -65] + DstBlock "3D Graphical Simulation1" + DstPort 2 + } + Line { + ZOrder 62 + SrcBlock "B_vo_dot" + SrcPort 1 + DstBlock "Delay2" + DstPort 1 + } + Line { + ZOrder 63 + SrcBlock "Delay2" + SrcPort 1 + DstBlock "IMU\n\n\n\n\n\n" + DstPort 1 + } + Line { + ZOrder 45 + SrcBlock "OptiTrack Camera System\n\n " + SrcPort 1 + Points [24, 0] + Branch { + ZOrder 235 + DstBlock "Transport\nDelay" + DstPort 1 + } + Branch { + ZOrder 208 + Points [0, 225] + DstBlock "First-Order\nHold1" + DstPort 1 + } + } + Line { + ZOrder 209 + SrcBlock "OptiTrack Camera System\n\n " + SrcPort 2 + Points [46, 0] + Branch { + ZOrder 234 + Points [0, 85] + DstBlock "First-Order\nHold" + DstPort 1 + } + Branch { + ZOrder 229 + DstBlock "Transport\nDelay1" + DstPort 1 + } + } + Line { + ZOrder 226 + SrcBlock "Transport\nDelay" + SrcPort 1 + DstBlock "Sample" + DstPort 1 + } + Line { + ZOrder 228 + SrcBlock "Transport\nDelay1" + SrcPort 1 + DstBlock "Sample1" + DstPort 1 + } + Line { + ZOrder 230 + SrcBlock "Sample" + SrcPort 1 + Points [110, 0] + Branch { + ZOrder 708 + Points [0, -75] + DstBlock "To Workspace4" + DstPort 1 + } + Branch { + ZOrder 707 + DstBlock "current_position" + DstPort 1 + } + } + Line { + ZOrder 295 + SrcBlock "Raw Accelerometer Data" + SrcPort 1 + Points [100, 0] + Branch { + ZOrder 414 + Points [83, 0; 0, -65; 48, 0] + Branch { + ZOrder 467 + Points [0, -150] + DstBlock "MATLAB Function1" + DstPort 1 + } + Branch { + ZOrder 466 + DstBlock "Calculate Pitch and Roll" + DstPort 1 + } + } + Branch { + ZOrder 297 + Points [0, 35] + DstBlock "Scope1" + DstPort 1 + } + } + Line { + ZOrder 298 + SrcBlock "Raw Gyroscope Data" + SrcPort 1 + Points [30, 0] + Branch { + ZOrder 413 + Points [66, 0] + Branch { + ZOrder 6 + Points [74, 0] + Branch { + ZOrder 561 + Points [0, 390] + DstBlock "Aeb_c\n\n\n\n\n\n\n\n\n\n1" + DstPort 1 + } + Branch { + ZOrder 316 + DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n" + DstPort 1 + } + } + Branch { + ZOrder 5 + Points [0, -35] + DstBlock "Scope" + DstPort 1 + } + } + Branch { + ZOrder 160 + Points [0, 50] + DstBlock "euler_rates" + DstPort 1 + } + } + Line { + ZOrder 342 + SrcBlock "Delay" + SrcPort 1 + Points [-179, 0] + Branch { + ZOrder 562 + Points [0, -75] + DstBlock "Complimentary Filter" + DstPort 4 + } + Branch { + ZOrder 565 + Points [0, 115; -374, 0; 0, 200] + DstBlock "Aeb_c\n\n\n\n\n\n\n\n\n\n1" + DstPort 2 + } + Branch { + ZOrder 411 + Points [-339, 0; 0, -75] + DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n" + DstPort 2 + } + } + Line { + ZOrder 416 + SrcBlock "euler_angles" + SrcPort 1 + DstBlock "Demux" + DstPort 1 + } + Line { + ZOrder 417 + SrcBlock "Demux" + SrcPort 3 + DstBlock "OptiTrack Camera System\n\n " + DstPort 2 + } + Line { + ZOrder 419 + SrcBlock "Sample1" + SrcPort 1 + Points [483, 0; 0, -800] + DstBlock "Mux" + DstPort 2 + } + Line { + ZOrder 420 + SrcBlock "Mux" + SrcPort 1 + DstBlock "euler_angles_filtered" + DstPort 1 + } + Line { + ZOrder 335 + SrcBlock "Complimentary Filter" + SrcPort 1 + Points [54, 0] + Branch { + ZOrder 665 + DstBlock "Mux" + DstPort 1 + } + Branch { + ZOrder 546 + Points [0, -125] + DstBlock "To Workspace5" + DstPort 1 + } + Branch { + ZOrder 533 + Points [0, 200] + Branch { + ZOrder 667 + DstBlock "Demux1" + DstPort 1 + } + Branch { + ZOrder 666 + DstBlock "Delay" + DstPort 1 + } + } + } + Line { + ZOrder 407 + SrcBlock "Aeb\n\n\n\n\n\n\n\n\n\n" + SrcPort 1 + Points [45, 0] + Branch { + ZOrder 560 + DstBlock "Scope4" + DstPort 1 + } + Branch { + ZOrder 558 + Points [108, 0] + Branch { + ZOrder 600 + Points [0, 435] + DstBlock "MATLAB Function" + DstPort 3 + } + Branch { + ZOrder 599 + Points [2, 0; 0, -55] + DstBlock "Complimentary Filter" + DstPort 3 + } + } + } + Line { + ZOrder 557 + SrcBlock "Aeb_c\n\n\n\n\n\n\n\n\n\n1" + SrcPort 1 + Points [35, 0; 0, -95] + DstBlock "Scope4" + DstPort 2 + } + Line { + ZOrder 604 + SrcBlock "MATLAB Function" + SrcPort 1 + Points [40, 0; 0, -70] + DstBlock "Demux2" + DstPort 1 + } + Line { + ZOrder 605 + SrcBlock "Demux1" + SrcPort 1 + Points [105, 0; 0, 10] + DstBlock "Scope5" + DstPort 1 + } + Line { + ZOrder 606 + SrcBlock "Demux2" + SrcPort 1 + Points [118, 0; 0, -155] + DstBlock "Scope5" + DstPort 2 + } + Line { + ZOrder 607 + SrcBlock "Demux1" + SrcPort 2 + Points [62, 0; 0, 80] + DstBlock "Scope6" + DstPort 1 + } + Line { + ZOrder 608 + SrcBlock "Demux2" + SrcPort 2 + Points [174, 0; 0, -85] + DstBlock "Scope6" + DstPort 2 + } + Line { + ZOrder 611 + SrcBlock "MATLAB Function1" + SrcPort 1 + DstBlock "Scope2" + DstPort 1 + } + Line { + ZOrder 614 + SrcBlock "MATLAB Function1" + SrcPort 2 + DstBlock "Scope3" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Actuation" + SID "436" + Ports [1, 6] + Position [955, 426, 1205, 654] + ZOrder 71 + ShowName off + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 42 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, 'P', 'texmode', 'on');\nport_label('output', 1, '^{B}Omega', 'texmode', 'on');\npor" + "t_label('output', 2, '\\Theta', 'texmode', 'on');\nport_label('output', 3, '^{B}v_o', 'texmode', 'on');\nport_label('" + "output', 4, '^{E}r_o', 'texmode', 'on');\nport_label('output', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('outpu" + "t', 6, '^{B}g', 'texmode', 'on');\ndisp('Actuation', 'texmode', 'on'); " + } + System { + Name "Actuation" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "125" + Block { + BlockType Inport + Name "P" + SID "437" + Position [-105, 393, -75, 407] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + SID "446" + Ports [2, 1] + Position [1395, 303, 1630, 452] + ZOrder 81 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 43 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '^B\\Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode'," + " 'on');\nport_label('output', 1, 'd\\Theta/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode', 'on');" + } + System { + Name "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "25" + Block { + BlockType Inport + Name "B_omega" + SID "446::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "euler_angles" + SID "446::22" + Position [20, 136, 40, 154] + ZOrder 13 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "446::24" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 15 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "446::23" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 7" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 14 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "euler_rates" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "446::25" + Position [460, 241, 480, 259] + ZOrder 16 + } + Block { + BlockType Outport + Name "euler_rates" + SID "446::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "B_omega" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "euler_angles" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "euler_rates" + ZOrder 3 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "euler_rates" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Demux + Name "Demux1" + SID "449" + Ports [1, 3] + Position [1830, 526, 1835, 574] + ZOrder 107 + ShowName off + Outputs "3" + DisplayOption "bar" + Port { + PortNumber 1 + Name "x position" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "y position" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "z position" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Demux + Name "Demux2" + SID "450" + Ports [1, 3] + Position [1830, 301, 1835, 349] + ZOrder 109 + ShowName off + Outputs "3" + DisplayOption "bar" + Port { + PortNumber 1 + Name "Roll" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "Pitch" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "Yaw" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Demux + Name "Demux3" + SID "451" + Ports [1, 3] + Position [1830, 406, 1835, 454] + ZOrder 117 + ShowName off + Outputs "3" + DisplayOption "bar" + Port { + PortNumber 1 + Name "Body x velocity" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "Body y velocity" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "Body z velocity" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Demux + Name "Demux4" + SID "452" + Ports [1, 3] + Position [1830, 161, 1835, 209] + ZOrder 115 + ShowName off + Outputs "3" + DisplayOption "bar" + Port { + PortNumber 1 + Name "Body roll velocity" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "Body pitch velocity" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "Body yaw velocity" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Demux + Name "Demux5" + SID "453" + Ports [1, 3] + Position [1830, 641, 1835, 689] + ZOrder 119 + ShowName off + Outputs "3" + DisplayOption "bar" + Port { + PortNumber 1 + Name "Body x acceleration" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "Body y acceleration" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "Body z acceleration" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType SubSystem + Name "ESC System" + SID "442" + Ports [1, 1] + Position [35, 282, 290, 518] + ZOrder 36 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 44 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, 'P', 'texmode', 'on');\nport_label('output', 1, 'Vb_{eff}', 'texmode', 'on')" + ";\ndisp('ESC System');" + } + System { + Name "ESC System" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "37" + Block { + BlockType Inport + Name "P" + SID "442::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "442::36" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 17 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "442::35" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 4" + Ports [1, 2] + Position [180, 105, 230, 165] + ZOrder 16 + FunctionName "sf_sfun" + Parameters "Pmax,Pmin,Vb" + PortCounts "[1 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "Vb_eff" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "442::37" + Position [460, 241, 480, 259] + ZOrder 18 + } + Block { + BlockType Outport + Name "Vb_eff" + SID "442::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 34 + SrcBlock "P" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "Vb_eff" + ZOrder 35 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "Vb_eff" + DstPort 1 + } + Line { + ZOrder 36 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 37 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Gravity\n\n" + SID "443" + Ports [0, 1] + Position [335, 664, 485, 786] + ZOrder 96 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 45 + $ClassName "Simulink.Mask" + Display "port_label('output', 1, '^EF_g', 'texmode', 'on');\nfprintf('Gravity');\n" + } + System { + Name "Gravity\n\n" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "30" + Block { + BlockType Demux + Name " Demux " + SID "443::28" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 19 + Outputs "1" + } + Block { + BlockType Ground + Name " Ground " + SID "443::30" + Position [20, 121, 40, 139] + ZOrder 21 + } + Block { + BlockType S-Function + Name " SFunction " + SID "443::27" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 1" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 18 + FunctionName "sf_sfun" + Parameters "g,m" + PortCounts "[1 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "E_Fg" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "443::29" + Position [460, 241, 480, 259] + ZOrder 20 + } + Block { + BlockType Outport + Name "E_Fg" + SID "443::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + Name "E_Fg" + ZOrder 1 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "E_Fg" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock " Ground " + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Integrator + Name "Integrator" + SID "454" + Ports [1, 1] + Position [740, 340, 770, 370] + ZOrder 49 + InitialCondition "[omega0_o, omega1_o, omega2_o, omega3_o]" + } + Block { + BlockType Integrator + Name "Integrator1" + SID "455" + Ports [1, 1] + Position [1225, 445, 1255, 475] + ZOrder 53 + InitialCondition "[x_vel_o; y_vel_o; z_vel_o]" + } + Block { + BlockType Integrator + Name "Integrator2" + SID "456" + Ports [1, 1] + Position [1225, 325, 1255, 355] + ZOrder 54 + InitialCondition "[rollrate_o; pitchrate_o; yawrate_o]" + } + Block { + BlockType Integrator + Name "Integrator3" + SID "457" + Ports [1, 1] + Position [1685, 590, 1715, 620] + ZOrder 98 + InitialCondition "[x_o; y_o; z_o]" + } + Block { + BlockType Integrator + Name "Integrator4" + SID "458" + Ports [1, 1] + Position [1685, 365, 1715, 395] + ZOrder 77 + InitialCondition "[roll_o; pitch_o; yaw_o]" + ContinuousStateAttributes "['phi' 'theta' 'psi']" + } + Block { + BlockType SubSystem + Name "Lbe\n\n\n\n\n\n" + SID "444" + Ports [2, 1] + Position [1395, 499, 1630, 706] + ZOrder 75 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 46 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '^Bv_o', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" + "');\nport_label('output', 1, '^Ev_o', 'texmode', 'on');\ndisp('L_{EB}', 'texmode', 'on');" + } + System { + Name "Lbe\n\n\n\n\n\n" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "31" + Block { + BlockType Inport + Name "B_vo" + SID "444::24" + Position [20, 101, 40, 119] + ZOrder 15 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "euler_angles" + SID "444::28" + Position [20, 136, 40, 154] + ZOrder 19 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "444::30" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 21 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "444::29" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 2" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 20 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "E_ro" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "444::31" + Position [460, 241, 480, 259] + ZOrder 22 + } + Block { + BlockType Outport + Name "E_ro" + SID "444::26" + Position [460, 101, 480, 119] + ZOrder 17 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "B_vo" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "euler_angles" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "E_ro" + ZOrder 3 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "E_ro" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + SID "447" + Ports [2, 2] + Position [600, 694, 770, 816] + ZOrder 97 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 47 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '^EF_g', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" + "');\nport_label('output', 1, '^BF_g', 'texmode', 'on');\nport_label('output', 2, '^Bg', 'texmode', 'on');\ndisp('" + "L_{BE}', 'texmode', 'on');" + } + System { + Name "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "33" + Block { + BlockType Inport + Name "E_Fg" + SID "447::24" + Position [20, 101, 40, 119] + ZOrder 15 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "euler_angles" + SID "447::28" + Position [20, 136, 40, 154] + ZOrder 19 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "447::30" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 21 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "447::29" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 8" + Ports [2, 3] + Position [180, 100, 230, 180] + ZOrder 20 + FunctionName "sf_sfun" + Parameters "m" + PortCounts "[2 3]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "B_Fg" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "B_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "447::31" + Position [460, 241, 480, 259] + ZOrder 22 + } + Block { + BlockType Outport + Name "B_Fg" + SID "447::26" + Position [460, 101, 480, 119] + ZOrder 17 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "B_g" + SID "447::32" + Position [460, 136, 480, 154] + ZOrder 23 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "E_Fg" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "euler_angles" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "B_Fg" + ZOrder 3 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "B_Fg" + DstPort 1 + } + Line { + Name "B_g" + ZOrder 4 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "B_g" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Motor System" + SID "441" + Ports [2, 1] + Position [420, 280, 640, 520] + ZOrder 48 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 48 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, 'Vb_{eff}', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', " + "'on');\nport_label('output', 1, '\\alpha', 'texmode', 'on');\ndisp('Motor System');\n" + } + System { + Name "Motor System" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "35" + Block { + BlockType Inport + Name "Vb_eff" + SID "441::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "w" + SID "441::35" + Position [20, 136, 40, 154] + ZOrder 20 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "441::32" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 17 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "441::31" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 5" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 16 + FunctionName "sf_sfun" + Parameters "If,Jreq,Kd,Kq,Kv,Rm" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "w_dot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "441::33" + Position [460, 241, 480, 259] + ZOrder 18 + } + Block { + BlockType Outport + Name "w_dot" + SID "441::23" + Position [460, 101, 480, 119] + ZOrder 14 + IconDisplay "Port number" + } + Line { + ZOrder 33 + SrcBlock "Vb_eff" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 34 + SrcBlock "w" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "w_dot" + ZOrder 35 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "w_dot" + DstPort 1 + } + Line { + ZOrder 36 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 37 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Rotor System\n\n\n\n\n\n\n\n" + SID "758" + Ports [5, 2] + Position [945, 281, 1145, 519] + ZOrder 122 + ShowName off + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 49 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, '\\alpha', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', '" + "on');\nport_label('input', 3, '^BF_g', 'texmode', 'on');\nport_label('input', 4, '^B\\Omega', 'texmode', 'on');\n" + "port_label('input', 5, '^Bv_o', 'texmode', 'on');\nport_label('output', 1, '^Bd\\Omega/dt', 'texmode', 'on');\npo" + "rt_label('output', 2, '^Bdv_o/dt', 'texmode', 'on');\ndisp('Rotor System', 'texmode', 'on');" + } + System { + Name "Rotor System\n\n\n\n\n\n\n\n" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "51" + Block { + BlockType Inport + Name "w_dot" + SID "758::27" + Position [20, 101, 40, 119] + ZOrder 18 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "w" + SID "758::28" + Position [20, 136, 40, 154] + ZOrder 19 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "B_Fg" + SID "758::47" + Position [20, 171, 40, 189] + ZOrder 20 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "B_omega" + SID "758::25" + Position [20, 206, 40, 224] + ZOrder 16 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "B_vo" + SID "758::24" + Position [20, 246, 40, 264] + ZOrder 15 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "758::49" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 22 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "758::48" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 6" + Ports [5, 3] + Position [180, 100, 230, 220] + ZOrder 21 + FunctionName "sf_sfun" + Parameters "Jreq,Jxx,Jyy,Jzz,Kd,Kt,m,rhx,rhy,rhz" + PortCounts "[5 3]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "B_omega_dot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "B_vo_dot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "758::50" + Position [460, 241, 480, 259] + ZOrder 23 + } + Block { + BlockType Outport + Name "B_omega_dot" + SID "758::22" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "B_vo_dot" + SID "758::5" + Position [460, 136, 480, 154] + ZOrder -5 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 29 + SrcBlock "w_dot" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 30 + SrcBlock "w" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 31 + SrcBlock "B_Fg" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 32 + SrcBlock "B_omega" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + ZOrder 33 + SrcBlock "B_vo" + SrcPort 1 + DstBlock " SFunction " + DstPort 5 + } + Line { + Name "B_omega_dot" + ZOrder 34 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "B_omega_dot" + DstPort 1 + } + Line { + Name "B_vo_dot" + ZOrder 35 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "B_vo_dot" + DstPort 1 + } + Line { + ZOrder 36 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 37 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Scope + Name "Scope" + SID "459" + Ports [1] + Position [350, 279, 380, 311] + ZOrder 46 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData + YMin -0.88633 + YMax 7.97693 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope1" + SID "460" + Ports [1] + Position [740, 229, 770, 261] + ZOrder 50 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -4063.58997 + YMax 3472.27662 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope10" + SID "461" + Ports [3] + Position [1935, 303, 1975, 347] + ZOrder 108 + NumInputPorts "3" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -1.00000~-1.00000~-1.00000 + YMax 1.00000~1.00000~1.00000 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + axes3 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope11" + SID "462" + Ports [3] + Position [1935, 163, 1975, 207] + ZOrder 114 + NumInputPorts "3" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData3 + YMin -1.00000~-1.00000~-1.00000 + YMax 1.00000~1.00000~1.00000 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + axes3 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope2" + SID "463" + Ports [1] + Position [890, 229, 920, 261] + ZOrder 51 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData2 + YMin -87.04326 + YMax 669.47775 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope3" + SID "464" + Ports [3] + Position [1935, 408, 1975, 452] + ZOrder 116 + NumInputPorts "3" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData2 + YMin -1.00000~-1.00000~-0.000000000000004 + YMax 1.00000~1.00000~0.000000000000032 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + axes3 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope4" + SID "465" + Ports [3] + Position [1935, 643, 1975, 687] + ZOrder 118 + NumInputPorts "3" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData4 + YMin -1.00000~-1.00000~0.0000000000000004 + YMax 1.00000~1.00000~0.0000000000000024 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + axes3 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope5" + SID "1050" + Ports [1] + Position [1335, 364, 1365, 396] + ZOrder 316 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData3 + YMin -0.66996 + YMax 5.80636 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope6" + SID "466" + Ports [3] + Position [1935, 528, 1975, 572] + ZOrder 79 + NumInputPorts "3" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData4 + YMin -1.00000~-1.00000~-0.00000000000004 + YMax 1.00000~1.00000~0.00000000000032 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + axes3 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope7" + SID "467" + Ports [1] + Position [600, 639, 630, 671] + ZOrder 99 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -1.52545 + YMax 13.7291 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope8" + SID "468" + Ports [1] + Position [820, 629, 850, 661] + ZOrder 100 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData2 + YMin -14.59237 + YMax 14.59237 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Scope + Name "Scope9" + SID "469" + Ports [1] + Position [1225, 229, 1255, 261] + ZOrder 102 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData3 + YMin -1.00000 + YMax 1.00000 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] + } + Block { + BlockType Outport + Name "B_omega" + SID "471" + Position [1845, 238, 1875, 252] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "euler_angles" + SID "472" + Position [1845, 373, 1875, 387] + ZOrder 91 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "B_vo" + SID "473" + Position [1845, 473, 1875, 487] + ZOrder 58 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "E_ro" + SID "474" + Position [1845, 598, 1875, 612] + ZOrder 88 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "B_vo_dot" + SID "475" + Position [1845, 718, 1875, 732] + ZOrder 103 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "B_g" + SID "476" + Position [1845, 778, 1875, 792] + ZOrder 104 + Port "6" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "ESC System" + SrcPort 1 + Points [23, 0; 0, -60] + Branch { + ZOrder 2 + Points [0, -45] + DstBlock "Scope" + DstPort 1 + } + Branch { + ZOrder 3 + DstBlock "Motor System" + DstPort 1 + } + } + Line { + ZOrder 4 + SrcBlock "Motor System" + SrcPort 1 + Points [40, 0; 0, -45] + Branch { + ZOrder 5 + DstBlock "Integrator" + DstPort 1 + } + Branch { + ZOrder 6 + Points [0, -45] + Branch { + ZOrder 101 + DstBlock "Rotor System\n\n\n\n\n\n\n\n" DstPort 1 } - Line { - ZOrder 3 - SrcBlock "accelerometer_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum1" + Branch { + ZOrder 7 + Points [0, -65] + DstBlock "Scope1" DstPort 1 } - Line { - ZOrder 4 - SrcBlock "Sum" - SrcPort 1 - DstBlock "gyroscope_qunatizer" + } + } + Line { + ZOrder 103 + SrcBlock "Rotor System\n\n\n\n\n\n\n\n" + SrcPort 1 + Points [39, 0] + Branch { + ZOrder 15 + Points [0, -95] + DstBlock "Scope9" + DstPort 1 + } + Branch { + ZOrder 16 + DstBlock "Integrator2" + DstPort 1 + } + } + Line { + ZOrder 22 + SrcBlock "Integrator2" + SrcPort 1 + Points [55, 0] + Branch { + ZOrder 105 + Points [0, 252; -416, 0; 0, -147] + DstBlock "Rotor System\n\n\n\n\n\n\n\n" + DstPort 4 + } + Branch { + ZOrder 23 + Points [0, -95; 454, 0] + Branch { + ZOrder 24 + DstBlock "B_omega" DstPort 1 } - Line { - ZOrder 5 - SrcBlock "Sum2" - SrcPort 1 - DstBlock "Sum" + Branch { + ZOrder 25 + Points [0, -60] + DstBlock "Demux4" DstPort 1 } - Line { - ZOrder 6 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 7 - SrcBlock "\n\n\n\n\n\n\n" - SrcPort 2 - DstBlock "gyroscope_sampling" - DstPort 1 + } + Branch { + ZOrder 27 + DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + DstPort 1 + } + } + Line { + ZOrder 28 + SrcBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + SrcPort 1 + DstBlock "Integrator4" + DstPort 1 + } + Line { + ZOrder 32 + SrcBlock "Lbe\n\n\n\n\n\n" + SrcPort 1 + DstBlock "Integrator3" + DstPort 1 + } + Line { + ZOrder 33 + SrcBlock "Integrator3" + SrcPort 1 + Points [64, 0] + Branch { + ZOrder 34 + Points [0, -55] + DstBlock "Demux1" + DstPort 1 + } + Branch { + ZOrder 35 + DstBlock "E_ro" + DstPort 1 + } + } + Line { + ZOrder 36 + SrcBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + SrcPort 1 + Points [24, 0] + Branch { + ZOrder 368 + Points [0, -80] + DstBlock "Scope8" + DstPort 1 + } + Branch { + ZOrder 107 + Points [82, 0; 0, -325] + DstBlock "Rotor System\n\n\n\n\n\n\n\n" + DstPort 3 + } + } + Line { + ZOrder 39 + SrcBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + SrcPort 2 + DstBlock "B_g" + DstPort 1 + } + Line { + Name "y position" + ZOrder 45 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 2 + DstBlock "Scope6" + DstPort 2 + } + Line { + Name "x position" + ZOrder 46 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 1 + DstBlock "Scope6" + DstPort 1 + } + Line { + Name "z position" + ZOrder 47 + Labels [0, 0] + SrcBlock "Demux1" + SrcPort 3 + DstBlock "Scope6" + DstPort 3 + } + Line { + Name "Pitch" + ZOrder 57 + Labels [0, 0] + SrcBlock "Demux2" + SrcPort 2 + DstBlock "Scope10" + DstPort 2 + } + Line { + Name "Roll" + ZOrder 58 + Labels [0, 0] + SrcBlock "Demux2" + SrcPort 1 + DstBlock "Scope10" + DstPort 1 + } + Line { + Name "Yaw" + ZOrder 59 + Labels [0, 0] + SrcBlock "Demux2" + SrcPort 3 + DstBlock "Scope10" + DstPort 3 + } + Line { + Name "Body pitch velocity" + ZOrder 60 + Labels [0, 0] + SrcBlock "Demux4" + SrcPort 2 + DstBlock "Scope11" + DstPort 2 + } + Line { + Name "Body roll velocity" + ZOrder 61 + Labels [0, 0] + SrcBlock "Demux4" + SrcPort 1 + DstBlock "Scope11" + DstPort 1 + } + Line { + Name "Body yaw velocity" + ZOrder 62 + Labels [0, 0] + SrcBlock "Demux4" + SrcPort 3 + DstBlock "Scope11" + DstPort 3 + } + Line { + Name "Body y velocity" + ZOrder 63 + Labels [0, 0] + SrcBlock "Demux3" + SrcPort 2 + DstBlock "Scope3" + DstPort 2 + } + Line { + Name "Body x velocity" + ZOrder 64 + Labels [0, 0] + SrcBlock "Demux3" + SrcPort 1 + DstBlock "Scope3" + DstPort 1 + } + Line { + Name "Body z velocity" + ZOrder 65 + Labels [0, 0] + SrcBlock "Demux3" + SrcPort 3 + DstBlock "Scope3" + DstPort 3 + } + Line { + Name "Body y acceleration" + ZOrder 66 + Labels [0, 0] + SrcBlock "Demux5" + SrcPort 2 + DstBlock "Scope4" + DstPort 2 + } + Line { + Name "Body x acceleration" + ZOrder 67 + Labels [0, 0] + SrcBlock "Demux5" + SrcPort 1 + DstBlock "Scope4" + DstPort 1 + } + Line { + Name "Body z acceleration" + ZOrder 68 + Labels [0, 0] + SrcBlock "Demux5" + SrcPort 3 + DstBlock "Scope4" + DstPort 3 + } + Line { + ZOrder 69 + SrcBlock "Integrator1" + SrcPort 1 + Points [34, 0] + Branch { + ZOrder 414 + Points [0, -80] + DstBlock "Scope5" + DstPort 1 + } + Branch { + ZOrder 413 + Points [0, 90] + Branch { + ZOrder 104 + Points [-370, 0; 0, -60] + DstBlock "Rotor System\n\n\n\n\n\n\n\n" + DstPort 5 } - Line { - ZOrder 8 - SrcBlock "gyroscope_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum" - DstPort 2 + Branch { + ZOrder 71 + Points [76, 0] + Branch { + ZOrder 72 + DstBlock "Lbe\n\n\n\n\n\n" + DstPort 1 + } + Branch { + ZOrder 73 + Points [0, -70; 401, 0] + Branch { + ZOrder 367 + Points [0, -50] + DstBlock "Demux3" + DstPort 1 + } + Branch { + ZOrder 75 + DstBlock "B_vo" + DstPort 1 + } + } } - Line { - ZOrder 9 - SrcBlock "\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "accelerometer_sampling" + } + } + Line { + ZOrder 102 + SrcBlock "Rotor System\n\n\n\n\n\n\n\n" + SrcPort 2 + Points [27, 0] + Branch { + ZOrder 205 + Points [0, 265; 607, 0] + Branch { + ZOrder 201 + Points [0, -60] + DstBlock "Demux5" DstPort 1 } - Line { - ZOrder 10 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "accelerometer_quantizer" + Branch { + ZOrder 200 + DstBlock "B_vo_dot" DstPort 1 } - Line { - ZOrder 11 - SrcBlock "gyroscope_sampling" - SrcPort 1 - DstBlock "Sum2" + } + Branch { + ZOrder 198 + DstBlock "Integrator1" + DstPort 1 + } + } + Line { + ZOrder 48 + SrcBlock "Integrator4" + SrcPort 1 + Points [20, 0] + Branch { + ZOrder 277 + Points [60, 0] + Branch { + ZOrder 361 + DstBlock "euler_angles" DstPort 1 } - Line { - ZOrder 12 - SrcBlock "accelerometer_sampling" - SrcPort 1 - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 13 - SrcBlock "Ground" - SrcPort 1 - Points [5, 0] - DstBlock "Sum2" - DstPort 2 - } - Line { - ZOrder 14 - SrcBlock "Ground1" - SrcPort 1 - Points [5, 0] - DstBlock "Sum3" + Branch { + ZOrder 360 + Points [0, -55] + DstBlock "Demux2" DstPort 1 } - Line { - ZOrder 15 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 1 + } + Branch { + ZOrder 52 + Points [0, 502; -385, 0] + Branch { + ZOrder 352 + Points [0, -227] + Branch { + ZOrder 54 + DstBlock "Lbe\n\n\n\n\n\n" + DstPort 2 + } + Branch { + ZOrder 55 + Points [0, -240] + DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + DstPort 2 + } } - Line { - ZOrder 16 - SrcBlock "B_vo" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" + Branch { + ZOrder 56 + Points [-787, 0; 0, -97] + DstBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" DstPort 2 } - Line { - ZOrder 17 - SrcBlock "B_Omega" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 3 - } - Line { - ZOrder 18 - SrcBlock "B_g" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 4 - } - Line { - ZOrder 19 - SrcBlock "r_oc" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 5 - } } } + Line { + ZOrder 286 + SrcBlock "P" + SrcPort 1 + DstBlock "ESC System" + DstPort 1 + } + Line { + ZOrder 416 + SrcBlock "Gravity\n\n" + SrcPort 1 + Points [86, 0] + Branch { + ZOrder 410 + Points [0, -70] + DstBlock "Scope7" + DstPort 1 + } + Branch { + ZOrder 409 + DstBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + DstPort 1 + } + } + Line { + ZOrder 415 + SrcBlock "Integrator" + SrcPort 1 + Points [58, 0] + Branch { + ZOrder 290 + Points [0, 210; -473, 0; 0, -105] + DstBlock "Motor System" + DstPort 2 + } + Branch { + ZOrder 292 + DstBlock "Rotor System\n\n\n\n\n\n\n\n" + DstPort 2 + } + Branch { + ZOrder 291 + Points [0, -110] + DstBlock "Scope2" + DstPort 1 + } + } + } + } + Block { + BlockType SubSystem + Name "Communication System" + SID "582" + Ports [0, 1] + Position [515, 432, 570, 478] + ZOrder 70 + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 50 + $ClassName "Simulink.Mask" + Display "port_label('output', 1, 'Setpoints', 'texmode', 'on');" + } + System { + Name "Communication System" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "175" + Block { + BlockType Step + Name "Step" + SID "583" + Position [925, 390, 955, 420] + ZOrder 32 + Before "[0; 0; 0; 0]" + After "[0; 0; 0; 0]" + SampleTime "Tq" + } + Block { + BlockType Outport + Name "setpoints" + SID "584" + Position [1050, 398, 1080, 412] + ZOrder 6 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "Step" + SrcPort 1 + DstBlock "setpoints" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Control System" + SID "573" + Ports [4, 1] + Position [645, 423, 900, 652] + ZOrder 69 + ShowName off + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 51 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, 'Setpoints', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{filtered}', 'texmo" + "de', 'on');\nport_label('input', 3, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmo" + "de', 'on');\nport_label('output', 1, 'P', 'texmode', 'on');\ndisp('Control System', 'texmode', 'on');" + } + System { + Name "Control System" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "80" + Block { + BlockType Inport + Name "setpoints" + SID "574" + Position [215, 363, 245, 377] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "euler_angles_filtered" + SID "575" + Position [215, 523, 245, 537] + ZOrder 9 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "euler_rates" + SID "576" + Position [215, 598, 245, 612] + ZOrder 11 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "current_position" + SID "577" + Position [215, 448, 245, 462] + ZOrder -1 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Constant + Name "Constant" + SID "919" + Position [275, 1020, 305, 1050] + ZOrder 66 + Value "Tc" + SampleTime "Tc" + } Block { BlockType SubSystem - Name "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SID "892" - Ports [2, 1] - Position [1470, 689, 1885, 811] - ZOrder 275 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on + Name "Controller" + SID "604" + Ports [13, 4] + Position [395, 315, 530, 645] + ZOrder 31 RequestExecContextInheritance off - SFBlockType "MATLAB Function" Variant off Object { $PropName "MaskObject" - $ObjectID 35 + $ObjectID 52 $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU" - "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{IMU}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode', " - "'on');" + Display "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se" + "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', " + "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'" + ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\" + "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't" + "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '" + "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode" + "', 'on');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\npo" + "rt_label('output', 4, 'u_R', 'texmode', 'on');\ndisp('Controller', 'texmode', 'on');" } System { - Name "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] + Name "Controller" + Location [-8, -8, 1928, 1048] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -4200,763 +8039,3370 @@ Model { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "25" + ZoomFactor "300" Block { BlockType Inport - Name "gyro_reading" - SID "892::1" - Position [20, 101, 40, 119] + Name "x_setpoint" + SID "605" + Position [475, -217, 505, -203] ZOrder -1 IconDisplay "Port number" } Block { BlockType Inport - Name "euler_angles_IMU" - SID "892::22" - Position [20, 136, 40, 154] - ZOrder 13 + Name "y_setpoint" + SID "607" + Position [475, -477, 505, -463] + ZOrder 45 + ForegroundColor "gray" Port "2" IconDisplay "Port number" } Block { - BlockType Demux - Name " Demux " - SID "892::24" + BlockType Inport + Name "z_setpoint" + SID "608" + Position [475, -717, 505, -703] + ZOrder 46 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "yaw_setpoint" + SID "632" + Position [475, 53, 505, 67] + ZOrder 103 + ForegroundColor "gray" + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "x_position" + SID "622" + Position [545, -172, 575, -158] + ZOrder 60 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "y_position" + SID "623" + Position [540, -432, 570, -418] + ZOrder 61 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "z_position" + SID "624" + Position [555, -662, 585, -648] + ZOrder 62 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "roll" + SID "630" + Position [835, -432, 865, -418] + ZOrder 68 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "pitch" + SID "631" + Position [840, -172, 870, -158] + ZOrder 69 + Port "9" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "yaw" + SID "649" + Position [560, 98, 590, 112] + ZOrder 105 + Port "10" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "roll_rate" + SID "633" + Position [1095, -432, 1125, -418] + ZOrder 71 + Port "11" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "pitch_rate" + SID "634" + Position [1090, -172, 1120, -158] + ZOrder 72 + Port "12" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "yaw_rate" + SID "635" + Position [820, 118, 850, 132] + ZOrder 73 + Port "13" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Altitude Controller Input" + SID "1177" + Ports [1, 1] + Position [685, -727, 750, -693] + ZOrder 292 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 53 + $ClassName "Simulink.Mask" + Display "disp('^Ez_{y,error}', 'texmode', 'on');" + } + System { + Name "Altitude Controller Input" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "200" + Block { + BlockType Inport + Name "z_error_model" + SID "1250" + Position [85, 123, 115, 137] + ZOrder 290 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1251" + Ports [1, 1] + Position [215, 151, 285, 189] + ZOrder 289 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 54 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "z_error_model" + SID "1252" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "z_error" + SID "1253" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "z_error_model" + SrcPort 1 + DstBlock "z_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "z error" + SID "1090" + Ports [0, 1] + Position [215, 78, 285, 112] + ZOrder 280 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 55 + $ClassName "Simulink.Mask" + Display "disp('^Er_{z,error}', 'texmode', 'on');" + } + System { + Name "z error" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "200" + Block { + BlockType FromWorkspace + Name "From\nWorkspace6" + SID "999" + Position [15, 18, 80, 42] + ZOrder 221 + VariableName "z_error" + SampleTime "Tc" + ZeroCross on + } + Block { + BlockType Outport + Name "z_error" + SID "1093" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace6" + SrcPort 1 + DstBlock "z_error" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "z_error" + SID "1184" + Position [400, 123, 430, 137] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1186" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType Gain + Name "Gain" + SID "880" + Position [935, -135, 965, -105] + ZOrder 149 + Gain "180/pi" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain1" + SID "1021" + Position [930, 135, 960, 165] + ZOrder 242 + Gain "180/pi" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain2" + SID "980" + Position [935, -395, 965, -365] + ZOrder 202 + Gain "180/pi" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType SubSystem + Name "Latitude Controller Input" + SID "1127" + Ports [1, 1] + Position [675, -227, 740, -193] + ZOrder 287 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 56 + $ClassName "Simulink.Mask" + Display "disp('^Er_{x,error}', 'texmode', 'on');" + } + System { + Name "Latitude Controller Input" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "x_error_model" + SID "1226" + Position [85, 158, 115, 172] + ZOrder 286 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1227" + Ports [1, 1] + Position [185, 146, 255, 184] + ZOrder 285 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 57 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "x_error_model" + SID "1228" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "x_error" + SID "1229" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "x_error_model" + SrcPort 1 + DstBlock "x_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "x error" + SID "1059" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 278 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 58 + $ClassName "Simulink.Mask" + Display "disp('^Er_{x,error}', 'texmode', 'on');" + } + System { + Name "x error" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "300" + Block { + BlockType FromWorkspace + Name "From\nWorkspace" + SID "947" + Position [20, 18, 85, 42] + ZOrder 171 + VariableName "x_error" + SampleTime "Tc" + ZeroCross on + } + Block { + BlockType Outport + Name "x_error" + SID "1060" + Position [230, 23, 260, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace" + SrcPort 1 + DstBlock "x_error" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "x_error" + SID "1134" + Position [405, 128, 435, 142] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1136" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType SubSystem + Name "Longitude Controller Input" + SID "1147" + Ports [1, 1] + Position [670, -487, 735, -453] + ZOrder 289 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 59 + $ClassName "Simulink.Mask" + Display "disp('^Er_{y,error}', 'texmode', 'on');" + } + System { + Name "Longitude Controller Input" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "y_error_model" + SID "1238" + Position [85, 173, 115, 187] + ZOrder 288 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1239" + Ports [1, 1] + Position [185, 161, 255, 199] + ZOrder 287 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 60 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "y_error_model" + SID "1240" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "y_error" + SID "1241" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "y_error_model" + SrcPort 1 + DstBlock "y_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "y error" + SID "1078" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 279 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 61 + $ClassName "Simulink.Mask" + Display "disp('^Er_{y,error}', 'texmode', 'on');" + } + System { + Name "y error" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "200" + Block { + BlockType FromWorkspace + Name "From\nWorkspace3" + SID "977" + Position [15, 18, 80, 42] + ZOrder 207 + VariableName "y_error" + SampleTime "Tc" + ZeroCross on + } + Block { + BlockType Outport + Name "y_error" + SID "1081" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace3" + SrcPort 1 + DstBlock "y_error" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "y_error" + SID "1154" + Position [385, 123, 415, 137] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1156" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType Reference + Name "PID Controller1" + SID "1355" + Ports [1, 1] + Position [1045, 41, 1085, 79] + ZOrder 313 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "P" + TimeDomain "Discrete-time" + SampleTime "Tq" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter on + ControllerParametersSource "internal" + P "29700" + I "-77.7" + D "2.32" + N "1/0.0818" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross off + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" + } + Block { + BlockType Reference + Name "PID Controller11" + SID "1370" + Ports [1, 1] + Position [790, -229, 830, -191] + ZOrder 321 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PID" + TimeDomain "Discrete-time" + SampleTime "Tc" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter on + ControllerParametersSource "internal" + P "-0.015" + I "0" + D "-0.25" + N "3" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" + } + Block { + BlockType Reference + Name "PID Controller17" + SID "1352" + Ports [1, 1] + Position [790, -728, 830, -692] + ZOrder 310 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PID" + TimeDomain "Discrete-time" + SampleTime "Tc" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter off + ControllerParametersSource "internal" + P "9804" + I "817" + D "7353" + N "5.79502261645411" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" + } + Block { + BlockType Reference + Name "PID Controller2" + SID "1424" Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 15 - Outputs "1" + Position [1045, -488, 1085, -452] + ZOrder 326 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PD" + TimeDomain "Discrete-time" + SampleTime "Tq" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter off + ControllerParametersSource "internal" + P "15" + I "35.1207902652377" + D "0.2" + N "40.0107970227961" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" } Block { - BlockType S-Function - Name " SFunction " - SID "892::23" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 12" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 14 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_rates_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } + BlockType Reference + Name "PID Controller3" + SID "1423" + Ports [1, 1] + Position [1295, -488, 1335, -452] + ZOrder 325 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PD" + TimeDomain "Discrete-time" + SampleTime "Tq" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter off + ControllerParametersSource "internal" + P "4600" + I "1575.82088970639" + D "550" + N "244.660686071579" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" } Block { - BlockType Terminator - Name " Terminator " - SID "892::25" - Position [460, 241, 480, 259] - ZOrder 16 + BlockType Reference + Name "PID Controller4" + SID "1354" + Ports [1, 1] + Position [790, 42, 830, 78] + ZOrder 312 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PD" + TimeDomain "Discrete-time" + SampleTime "Tc" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter off + ControllerParametersSource "internal" + P "2.6" + I "2.36803176515497" + D "0" + N "3.83298618768959" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" } Block { - BlockType Outport - Name "euler_rates_IMU" - SID "892::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" + BlockType Reference + Name "PID Controller5" + SID "1368" + Ports [1, 1] + Position [1045, -228, 1085, -192] + ZOrder 319 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PD" + TimeDomain "Discrete-time" + SampleTime "Tq" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter off + ControllerParametersSource "internal" + P "15" + I "35.1207902652377" + D "0.2" + N "40.0107970227961" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" } - Line { - ZOrder 1 - SrcBlock "gyro_reading" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 + Block { + BlockType Reference + Name "PID Controller7" + SID "1365" + Ports [1, 1] + Position [790, -488, 830, -452] + ZOrder 316 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PID" + TimeDomain "Discrete-time" + SampleTime "Tc" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter on + ControllerParametersSource "internal" + P "0.015" + I "0" + D "0.25" + N "3" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" } - Line { - ZOrder 2 - SrcBlock "euler_angles_IMU" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 + Block { + BlockType Reference + Name "PID Controller9" + SID "1367" + Ports [1, 1] + Position [1295, -228, 1335, -192] + ZOrder 318 + LibraryVersion "1.388" + SourceBlock "simulink/Continuous/PID Controller" + SourceType "PID 1dof" + ContentPreviewEnabled off + Controller "PD" + TimeDomain "Discrete-time" + SampleTime "Tq" + IntegratorMethod "Forward Euler" + FilterMethod "Forward Euler" + Form "Parallel" + UseFilter off + ControllerParametersSource "internal" + P "4600" + I "1575.82088970639" + D "550" + N "244.660686071579" + InitialConditionSource "internal" + InitialConditionForIntegrator "0" + InitialConditionForFilter "0" + ExternalReset "none" + IgnoreLimit off + ZeroCross on + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + LinearizeAsGain on + AntiWindupMode "none" + Kb "1" + TrackingMode off + Kt "1" + RndMeth "Floor" + SaturateOnIntegerOverflow off + LockScale off + PParamMin "[]" + PParamMax "[]" + PParamDataTypeStr "Inherit: Inherit via internal rule" + IParamMin "[]" + IParamMax "[]" + IParamDataTypeStr "Inherit: Inherit via internal rule" + DParamMin "[]" + DParamMax "[]" + DParamDataTypeStr "Inherit: Inherit via internal rule" + NParamMin "[]" + NParamMax "[]" + NParamDataTypeStr "Inherit: Inherit via internal rule" + KbParamMin "[]" + KbParamMax "[]" + KbParamDataTypeStr "Inherit: Inherit via internal rule" + KtParamMin "[]" + KtParamMax "[]" + KtParamDataTypeStr "Inherit: Inherit via internal rule" + POutMin "[]" + POutMax "[]" + POutDataTypeStr "Inherit: Inherit via internal rule" + PGainOutDataTypeStr "Inherit: Inherit via internal rule" + PProdOutDataTypeStr "Inherit: Inherit via internal rule" + IOutMin "[]" + IOutMax "[]" + IOutDataTypeStr "Inherit: Inherit via internal rule" + IGainOutDataTypeStr "Inherit: Inherit via internal rule" + IProdOutDataTypeStr "Inherit: Inherit via internal rule" + DOutMin "[]" + DOutMax "[]" + DOutDataTypeStr "Inherit: Inherit via internal rule" + DGainOutDataTypeStr "Inherit: Inherit via internal rule" + DProdOutDataTypeStr "Inherit: Inherit via internal rule" + NOutMin "[]" + NOutMax "[]" + NOutDataTypeStr "Inherit: Inherit via internal rule" + NGainOutDataTypeStr "Inherit: Inherit via internal rule" + NProdOutDataTypeStr "Inherit: Inherit via internal rule" + KbOutMin "[]" + KbOutMax "[]" + KbOutDataTypeStr "Inherit: Inherit via internal rule" + KtOutMin "[]" + KtOutMax "[]" + KtOutDataTypeStr "Inherit: Inherit via internal rule" + IntegratorOutMin "[]" + IntegratorOutMax "[]" + IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" + FilterOutMin "[]" + FilterOutMax "[]" + FilterOutDataTypeStr "Inherit: Inherit via internal rule" + SumOutMin "[]" + SumOutMax "[]" + SumOutDataTypeStr "Inherit: Inherit via internal rule" + SumI1OutMin "[]" + SumI1OutMax "[]" + SumI1OutDataTypeStr "Inherit: Inherit via internal rule" + SumI2OutMin "[]" + SumI2OutMax "[]" + SumI2OutDataTypeStr "Inherit: Inherit via internal rule" + SumI3OutMin "[]" + SumI3OutMax "[]" + SumI3OutDataTypeStr "Inherit: Inherit via internal rule" + SumDOutMin "[]" + SumDOutMax "[]" + SumDOutDataTypeStr "Inherit: Inherit via internal rule" + SumAccumDataTypeStr "Inherit: Inherit via internal rule" + SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" + SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" + SumDAccumDataTypeStr "Inherit: Inherit via internal rule" + SaturationOutMin "[]" + SaturationOutMax "[]" + SaturationOutDataTypeStr "Inherit: Same as input" + IntegratorContinuousStateAttributes "''" + IntegratorStateMustResolveToSignalObject off + IntegratorRTWStateStorageClass "Auto" + FilterContinuousStateAttributes "''" + FilterStateMustResolveToSignalObject off + FilterRTWStateStorageClass "Auto" + DifferentiatorICPrevScaledInput "0" + DifferentiatorOutMin "[]" + DifferentiatorOutMax "[]" + DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" } - Line { - Name "euler_rates_IMU" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_rates_IMU" - DstPort 1 + Block { + BlockType SubSystem + Name "Pitch Controller Input" + SID "1103" + Ports [1, 1] + Position [940, -227, 1005, -193] + ZOrder 283 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 62 + $ClassName "Simulink.Mask" + Display "disp('\\theta_{error}', 'texmode', 'on');" + } + System { + Name "Pitch Controller Input" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "pitch_error_model" + SID "1230" + Position [85, 168, 115, 182] + ZOrder 286 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1231" + Ports [1, 1] + Position [185, 156, 255, 194] + ZOrder 285 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 63 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "pitch_error_model" + SID "1232" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "pitch_error" + SID "1233" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "pitch_error_model" + SrcPort 1 + DstBlock "pitch_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "pitch error" + SID "1066" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 274 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 64 + $ClassName "Simulink.Mask" + Display "disp('\\theta_{error}', 'texmode', 'on');" + } + System { + Name "pitch error" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType FromWorkspace + Name "From\nWorkspace" + SID "1068" + Position [20, 18, 85, 42] + ZOrder 171 + VariableName "pitch_error" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "pitch_error" + SID "1069" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace" + SrcPort 1 + DstBlock "pitch_error" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "pitch_error" + SID "1105" + Position [410, 123, 440, 137] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1106" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 + Block { + BlockType SubSystem + Name "Pitch Rate Controller Input" + SID "1137" + Ports [1, 1] + Position [1185, -227, 1250, -193] + ZOrder 288 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 65 + $ClassName "Simulink.Mask" + Display "disp('d\\theta/dt_{error}', 'texmode', 'on');" + } + System { + Name "Pitch Rate Controller Input" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "pitchrate_error_model" + SID "1234" + Position [85, 183, 115, 197] + ZOrder 286 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1235" + Ports [1, 1] + Position [185, 171, 255, 209] + ZOrder 285 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 66 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "pitchrate_error_model" + SID "1236" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "pitchrate_error" + SID "1237" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "pitchrate_error_model" + SrcPort 1 + DstBlock "pitchrate_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "pitchrate error" + SID "1074" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 278 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 67 + $ClassName "Simulink.Mask" + Display "disp('d\\theta/dt_{error}', 'texmode', 'on');" + } + System { + Name "pitchrate error" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType FromWorkspace + Name "From\nWorkspace2" + SID "950" + Position [10, 18, 80, 42] + ZOrder 175 + VariableName "pitchrate_error" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "pitchrate_error" + SID "1077" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace2" + SrcPort 1 + DstBlock "pitchrate_error" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "pitchrate_error" + SID "1144" + Position [410, 133, 440, 147] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1146" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 + Block { + BlockType SubSystem + Name "Roll Controller Input" + SID "1157" + Ports [1, 1] + Position [950, -487, 1015, -453] + ZOrder 290 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 68 + $ClassName "Simulink.Mask" + Display "disp('\\phi_{error}', 'texmode', 'on');" + } + System { + Name "Roll Controller Input" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "roll_error_model" + SID "1242" + Position [85, 158, 115, 172] + ZOrder 288 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1243" + Ports [1, 1] + Position [185, 146, 255, 184] + ZOrder 287 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 69 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "roll_error_model" + SID "1244" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "roll_error" + SID "1245" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "roll_error_model" + SrcPort 1 + DstBlock "roll_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "roll error" + SID "1082" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 278 + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 70 + $ClassName "Simulink.Mask" + Display "disp('\\phi_{error}', 'texmode', 'on');" + } + System { + Name "roll error" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType FromWorkspace + Name "From\nWorkspace4" + SID "978" + Position [190, 88, 255, 112] + ZOrder 209 + ForegroundColor "green" + VariableName "roll_error" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "roll_error" + SID "1085" + Position [315, 93, 345, 107] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace4" + SrcPort 1 + DstBlock "roll_error" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "roll_error" + SID "1164" + Position [410, 118, 440, 132] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1166" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType SubSystem + Name "Roll Rate Controller Input" + SID "1167" + Ports [1, 1] + Position [1200, -487, 1265, -453] + ZOrder 291 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 71 + $ClassName "Simulink.Mask" + Display "disp('d\\phi/dt_{error}', 'texmode', 'on');" + } + System { + Name "Roll Rate Controller Input" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "175" + Block { + BlockType Inport + Name "rollrate_error_model" + SID "1246" + Position [85, 163, 115, 177] + ZOrder 288 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1247" + Ports [1, 1] + Position [185, 151, 255, 189] + ZOrder 287 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 72 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "rollrate_error_model" + SID "1248" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "rollrate_error" + SID "1249" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "rollrate_error_model" + SrcPort 1 + DstBlock "rollrate_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "rollrate error" + SID "1086" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 279 + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 73 + $ClassName "Simulink.Mask" + Display "disp('d\\phi/dt_{error}', 'texmode', 'on');" + } + System { + Name "rollrate error" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType FromWorkspace + Name "From\nWorkspace5" + SID "979" + Position [10, 18, 80, 42] + ZOrder 210 + VariableName "rollrate_error" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "rollrate_error" + SID "1089" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace5" + SrcPort 1 + DstBlock "rollrate_error" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "rollrate_error" + SID "1174" + Position [405, 128, 435, 142] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1176" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } } - } - } - Block { - BlockType SubSystem - Name "\n\n\n\n\n\n\n\n\n\n\n\n1" - SID "908" - Ports [2, 2] - Position [1480, 484, 1875, 631] - ZOrder 284 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 36 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Accelerometer Reading', 'texmode', 'on');\nport_label('output', 1, '\\theta" - "_{accel}', 'texmode', 'on');\nport_label('output', 2, '\\phi_{accel}', 'texmode', 'on');\ndisp('Calculate Pitch a" - "nd Roll', 'texmode', 'on');" - } - System { - Name "\n\n\n\n\n\n\n\n\n\n\n\n1" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "26" Block { - BlockType Inport - Name "accel_reading" - SID "908::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" + BlockType Saturate + Name "Saturation" + SID "932" + Ports [1, 1] + Position [1380, 45, 1410, 75] + ZOrder 161 + InputPortMap "u0" + UpperLimit "20000" + LowerLimit "-20000" } Block { - BlockType Inport - Name "accel_roll_prev" - SID "908::23" - Position [20, 136, 40, 154] - ZOrder 14 - Port "2" - IconDisplay "Port number" + BlockType Saturate + Name "Saturation1" + SID "1001" + Ports [1, 1] + Position [1390, -225, 1420, -195] + ZOrder 222 + InputPortMap "u0" + UpperLimit "20000" + LowerLimit "-20000" } Block { - BlockType Demux - Name " Demux " - SID "908::20" + BlockType Saturate + Name "Saturation2" + SID "1002" Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" + Position [1390, -485, 1420, -455] + ZOrder 223 + InputPortMap "u0" + UpperLimit "20000" + LowerLimit "-20000" } Block { - BlockType S-Function - Name " SFunction " - SID "908::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 13" - Ports [2, 3] - Position [180, 105, 230, 185] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[2 3]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "accel_pitch" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" + BlockType Saturate + Name "Saturation3" + SID "1003" + Ports [1, 1] + Position [1390, -725, 1420, -695] + ZOrder 224 + InputPortMap "u0" + UpperLimit "20000" + LowerLimit "-20000" + } + Block { + BlockType Scope + Name "Scope1" + SID "1022" + Ports [1] + Position [990, 134, 1020, 166] + ZOrder 241 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData5 + YMin -237.62576 + YMax 9.97394 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" } - Port { - PortNumber 3 - Name "accel_roll" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" } + Location [680 330 1240 750] } Block { - BlockType Terminator - Name " Terminator " - SID "908::21" - Position [460, 241, 480, 259] - ZOrder 12 + BlockType Scope + Name "Scope11" + SID "984" + Ports [1] + Position [1215, -386, 1245, -354] + ZOrder 199 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints on + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData2 + YMin -1.23139 + YMax 0.20473 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat Array + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1909 1039] } Block { - BlockType Outport - Name "accel_pitch" - SID "908::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" + BlockType Scope + Name "Scope12" + SID "985" + Ports [1] + Position [645, -336, 675, -304] + ZOrder 200 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData3 + YMin -5094.66345 + YMax 568.26972 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] } Block { - BlockType Outport - Name "accel_roll" - SID "908::22" - Position [460, 136, 480, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 14 - SrcBlock "accel_reading" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 15 - SrcBlock "accel_roll_prev" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "accel_pitch" - ZOrder 16 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "accel_pitch" - DstPort 1 + BlockType Scope + Name "Scope13" + SID "986" + Ports [1] + Position [995, -396, 1025, -364] + ZOrder 201 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints on + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData4 + YMin -10 + YMax 10 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat Array + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [680 330 1240 750] } - Line { - Name "accel_roll" - ZOrder 17 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "accel_roll" - DstPort 1 + Block { + BlockType Scope + Name "Scope2" + SID "795" + Ports [1] + Position [665, -591, 695, -559] + ZOrder 107 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData5 + YMin -233.85726 + YMax 2104.70554 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] } - Line { - ZOrder 18 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 + Block { + BlockType Scope + Name "Scope3" + SID "1006" + Ports [1] + Position [655, 199, 685, 231] + ZOrder 226 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -171.38344 + YMax 42.10594 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] } - Line { - ZOrder 19 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 + Block { + BlockType Scope + Name "Scope4" + SID "1030" + Ports [1] + Position [650, -76, 680, -44] + ZOrder 250 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints on + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -227.57395 + YMax 29.15339 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat Array + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] } - } - } - Block { - BlockType SubSystem - Name "\n\n " - SID "989" - Ports [2, 2] - Position [1990, 946, 2230, 1039] - ZOrder 299 - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 37 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{E}r_o', 'texmode', 'on');\nport_label('input', 2, '\\psi', 'texmode', 'on" - "');\nport_label('output', 1, '^{E}r_o camera', 'texmode', 'on');\nport_label('output', 2, '\\psi camera', 'texmod" - "e', 'on');\ndisp('OptiTrack Camera System', 'texmode', 'on');" - } - System { - Name "\n\n " - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" Block { - BlockType Inport - Name "E_ro" - SID "990" - Position [295, 238, 325, 252] - ZOrder -1 - IconDisplay "Port number" + BlockType Scope + Name "Scope6" + SID "825" + Ports [1] + Position [1205, -126, 1235, -94] + ZOrder 117 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -32.40215 + YMax 23.21935 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] } Block { - BlockType Inport - Name "yaw" - SID "991" - Position [295, 338, 325, 352] - ZOrder 4 - Port "2" - IconDisplay "Port number" + BlockType Scope + Name "Scope9" + SID "878" + Ports [1] + Position [995, -136, 1025, -104] + ZOrder 147 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends off + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData1 + YMin -0.5042 + YMax 4.53783 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%<SignalLabel>" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [1 76 1921 1039] } Block { - BlockType RandomNumber - Name "E_ro_noise" - SID "992" - Position [545, 175, 575, 205] - ZOrder 30 - Mean "zeros(3,1)" - Variance "[ 7.9664e-10 ; 1.1928e-10 ; 5.0636e-10 ] " - Seed "[0,1,2]" - SampleTime "6.1e-3" + BlockType Sum + Name "Sum1" + SID "1007" + Ports [2, 1] + Position [610, 50, 630, 70] + ZOrder 225 + ForegroundColor "green" + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Quantizer - Name "E_ro_quantizer" - SID "993" - Position [685, 230, 715, 260] - ZOrder 34 - QuantizationInterval "2.4400e-04" + BlockType Sum + Name "Sum10" + SID "988" + Ports [2, 1] + Position [1140, -480, 1160, -460] + ZOrder 193 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType ZeroOrderHold - Name "E_ro_sampling" - SID "994" - Position [410, 230, 445, 260] - ZOrder 38 - SampleTime "6.1e-3" + BlockType Sum + Name "Sum11" + SID "989" + Ports [2, 1] + Position [610, -480, 630, -460] + ZOrder 194 + ForegroundColor "green" + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Ground - Name "Ground1" - SID "995" - Position [465, 180, 485, 200] - ZOrder 42 + BlockType Sum + Name "Sum2" + SID "1023" + Ports [2, 1] + Position [870, 50, 890, 70] + ZOrder 240 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { - BlockType Ground - Name "Ground2" - SID "996" - Position [465, 390, 485, 410] - ZOrder 56 + BlockType Sum + Name "Sum3" + SID "602" + Ports [2, 1] + Position [875, -220, 895, -200] + ZOrder 43 + ForegroundColor "green" + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off } Block { BlockType Sum - Name "Sum1" - SID "997" + Name "Sum4" + SID "603" Ports [2, 1] - Position [605, 235, 625, 255] - ZOrder 33 + Position [1130, -220, 1150, -200] + ZOrder 44 ShowName off IconShape "round" - Inputs "++|" + Inputs "|+-" InputSameDT off OutDataTypeStr "Inherit: Inherit via internal rule" SaturateOnIntegerOverflow off } Block { BlockType Sum - Name "Sum3" - SID "998" + Name "Sum5" + SID "618" Ports [2, 1] - Position [485, 235, 505, 255] - ZOrder 37 + Position [610, -220, 630, -200] + ZOrder 56 + ForegroundColor "green" ShowName off IconShape "round" - Inputs "++|" + Inputs "|+-" InputSameDT off OutDataTypeStr "Inherit: Inherit via internal rule" SaturateOnIntegerOverflow off } Block { BlockType Sum - Name "Sum4" - SID "999" + Name "Sum7" + SID "620" Ports [2, 1] - Position [605, 335, 625, 355] - ZOrder 47 + Position [610, -720, 630, -700] + ZOrder 58 ShowName off IconShape "round" - Inputs "|++" + Inputs "|+-" InputSameDT off OutDataTypeStr "Inherit: Inherit via internal rule" SaturateOnIntegerOverflow off } Block { BlockType Sum - Name "Sum6" - SID "1000" + Name "Sum9" + SID "987" Ports [2, 1] - Position [485, 335, 505, 355] - ZOrder 51 + Position [875, -480, 895, -460] + ZOrder 192 ShowName off IconShape "round" - Inputs "|++" + Inputs "|+-" InputSameDT off OutDataTypeStr "Inherit: Inherit via internal rule" SaturateOnIntegerOverflow off } Block { - BlockType RandomNumber - Name "yaw_noise" - SID "1001" - Position [545, 365, 575, 395] - ZOrder 46 - Variance "1.0783e-9" - SampleTime "6.1e-3" - } - Block { - BlockType Quantizer - Name "yaw_quantizer" - SID "1002" - Position [685, 330, 715, 360] - ZOrder 50 - QuantizationInterval "1.1e-3" - } - Block { - BlockType ZeroOrderHold - Name "yaw_sampling" - SID "1003" - Position [410, 330, 445, 360] - ZOrder 54 - SampleTime "6.1e-3" - } - Block { - BlockType Outport - Name "E_ro_camera" - SID "1004" - Position [800, 238, 830, 252] - ZOrder 43 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yaw_camera" - SID "1005" - Position [800, 338, 830, 352] - ZOrder 55 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "E_ro_quantizer" - SrcPort 1 - DstBlock "E_ro_camera" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "E_ro_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 4 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "E_ro_quantizer" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock "E_ro_sampling" - SrcPort 1 - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 6 - SrcBlock "Ground1" - SrcPort 1 - Points [5, 0] - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 7 - SrcBlock "yaw_quantizer" - SrcPort 1 - DstBlock "yaw_camera" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "Sum4" - SrcPort 1 - DstBlock "yaw_quantizer" - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock "Sum6" - SrcPort 1 - DstBlock "Sum4" - DstPort 1 - } - Line { - ZOrder 10 - SrcBlock "yaw_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum4" - DstPort 2 - } - Line { - ZOrder 11 - SrcBlock "yaw_sampling" - SrcPort 1 - DstBlock "Sum6" - DstPort 1 - } - Line { - ZOrder 12 - SrcBlock "Ground2" - SrcPort 1 - Points [5, 0] - DstBlock "Sum6" - DstPort 2 - } - Line { - ZOrder 13 - SrcBlock "yaw" - SrcPort 1 - DstBlock "yaw_sampling" - DstPort 1 - } - Line { - ZOrder 14 - SrcBlock "E_ro" - SrcPort 1 - DstBlock "E_ro_sampling" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "3D Graphical Simulation" - SID "911" - Ports [2] - Position [2005, 1075, 2155, 1135] - ZOrder 287 - Commented "on" - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 38 - $ClassName "Simulink.Mask" - Display "port_label('input',1,'r_{o}','texmode','on')\nport_label('input',2,'\\Theta','texmode','on')" - } - System { - Name "3D Graphical Simulation" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "60" - Block { - BlockType Inport - Name "Displacement" - SID "912" - Position [110, 218, 140, 232] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Euler Angles" - SID "913" - Position [125, 108, 155, 122] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType BusCreator - Name "Bus\nCreator" - SID "914" - Ports [3, 1] - Position [600, 76, 610, 154] - ZOrder -3 + BlockType ToWorkspace + Name "To Workspace" + SID "948" + Ports [1] + Position [875, -290, 985, -260] + ZOrder 172 ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on + VariableName "pitch_setpoint_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "-1" } Block { - BlockType BusCreator - Name "Bus\nCreator1" - SID "915" - Ports [3, 1] - Position [630, 191, 640, 269] - ZOrder -4 + BlockType ToWorkspace + Name "To Workspace1" + SID "951" + Ports [1] + Position [1125, -290, 1250, -260] + ZOrder 175 ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on + VariableName "pitchrate_setpoint_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" } Block { - BlockType BusCreator - Name "Bus\nCreator2" - SID "916" - Ports [3, 1] - Position [385, 75, 390, 155] - ZOrder -5 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on + BlockType ToWorkspace + Name "To Workspace10" + SID "1029" + Ports [1] + Position [650, 135, 770, 165] + ZOrder 249 + VariableName "yaw_value_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tc" } Block { - BlockType BusSelector - Name "Bus\nSelector" - SID "917" - Ports [1, 3] - Position [500, 77, 505, 153] - ZOrder -6 + BlockType ToWorkspace + Name "To Workspace11" + SID "1032" + Ports [1] + Position [645, -390, 765, -360] + ZOrder 252 ShowName off - OutputSignals "phi,theta,psi" - Port { - PortNumber 1 - Name "<phi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "<theta>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "<psi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } + VariableName "y_position_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tc" } Block { - BlockType Demux - Name "Demux" - SID "918" - Ports [1, 3] - Position [440, 183, 450, 267] - ZOrder -7 - BackgroundColor "black" + BlockType ToWorkspace + Name "To Workspace12" + SID "1033" + Ports [1] + Position [660, -640, 780, -610] + ZOrder 253 ShowName off - Outputs "3" - DisplayOption "bar" + VariableName "z_position_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tc" } Block { - BlockType Demux - Name "Demux1" - SID "919" - Ports [1, 3] - Position [290, 75, 295, 155] - ZOrder -8 + BlockType ToWorkspace + Name "To Workspace2" + SID "952" + Ports [1] + Position [1495, -290, 1605, -260] + ZOrder 176 + VariableName "x_command_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" + } + Block { + BlockType ToWorkspace + Name "To Workspace3" + SID "993" + Ports [1] + Position [895, -545, 1005, -515] + ZOrder 207 ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "phi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "theta" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "psi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } + VariableName "roll_setpoint_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tc" } Block { - BlockType Gain - Name "Gain" - SID "920" - Position [550, 240, 580, 270] - ZOrder -10 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + BlockType ToWorkspace + Name "To Workspace4" + SID "994" + Ports [1] + Position [1150, -545, 1275, -515] + ZOrder 210 + ShowName off + VariableName "rollrate_setpoint_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" } Block { - BlockType Gain - Name "Gain1" - SID "921" - Position [670, 208, 710, 252] - ZOrder -11 - Gain "eye(3)*1" - Multiplication "Matrix(K*u)" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + BlockType ToWorkspace + Name "To Workspace5" + SID "995" + Ports [1] + Position [1500, -545, 1610, -515] + ZOrder 211 + ForegroundColor "red" + VariableName "y_command_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" } Block { - BlockType Gain - Name "Gain2" - SID "922" - Position [550, 190, 580, 220] - ZOrder -12 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + BlockType ToWorkspace + Name "To Workspace6" + SID "1000" + Ports [1] + Position [1420, -805, 1530, -775] + ZOrder 327 + VariableName "z_command_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" + } + Block { + BlockType ToWorkspace + Name "To Workspace7" + SID "1025" + Ports [1] + Position [870, -20, 990, 10] + ZOrder 243 + ShowName off + VariableName "yawrate_setpoint_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tc" + } + Block { + BlockType ToWorkspace + Name "To Workspace8" + SID "1026" + Ports [1] + Position [1495, -20, 1605, 10] + ZOrder 247 + ShowName off + VariableName "yaw_command_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" + } + Block { + BlockType ToWorkspace + Name "To Workspace9" + SID "1028" + Ports [1] + Position [650, -135, 770, -105] + ZOrder 248 + ShowName off + VariableName "x_position_model" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tc" } Block { BlockType SubSystem - Name "MATLAB Function" - SID "923" + Name "Yaw Controller Input" + SID "1187" Ports [1, 1] - Position [655, 92, 725, 138] - ZOrder 5 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on + Position [675, 43, 740, 77] + ZOrder 293 + ForegroundColor "magenta" + ShowName off RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 74 + $ClassName "Simulink.Mask" + Display "disp('\\psi_{error}', 'texmode', 'on');" + } System { - Name "MATLAB Function" - Location [223, 338, 826, 833] + Name "Yaw Controller Input" + Location [-8, -8, 1928, 1048] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -4968,308 +11414,1036 @@ Model { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "21" + ZoomFactor "200" Block { BlockType Inport - Name "u" - SID "923::1" - Position [20, 101, 40, 119] - ZOrder -1 + Name "yaw_error_model" + SID "1216" + Position [50, 158, 80, 172] + ZOrder 282 IconDisplay "Port number" } Block { - BlockType Demux - Name " Demux " - SID "923::20" + BlockType SubSystem + Name "Feedback" + SID "1188" Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" + Position [185, 146, 255, 184] + ZOrder 276 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 75 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "yaw_error_model" + SID "1215" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "yaw_error" + SID "1190" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 2 + SrcBlock "yaw_error_model" + SrcPort 1 + DstBlock "yaw_error" + DstPort 1 + } + } } Block { - BlockType S-Function - Name " SFunction " - SID "923::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 11" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[1 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "y" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" + BlockType SubSystem + Name "yaw error" + SID "1094" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 281 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 76 + $ClassName "Simulink.Mask" + Display "disp('\\psi_{error}', 'texmode', 'on');" + } + System { + Name "yaw error" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType FromWorkspace + Name "From\nWorkspace7" + SID "1005" + Position [20, 18, 85, 42] + ZOrder 228 + VariableName "yaw_error" + SampleTime "Tc" + ZeroCross on + } + Block { + BlockType Outport + Name "yaw_error" + SID "1097" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace7" + SrcPort 1 + DstBlock "yaw_error" + DstPort 1 + } } } Block { - BlockType Terminator - Name " Terminator " - SID "923::21" - Position [460, 241, 480, 259] - ZOrder 12 + BlockType Outport + Name "yaw_error" + SID "1194" + Position [410, 123, 440, 137] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1196" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType SubSystem + Name "Yaw Rate Controller Input" + SID "1197" + Ports [1, 1] + Position [940, 43, 1005, 77] + ZOrder 294 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 77 + $ClassName "Simulink.Mask" + Display "disp('d\\psi/dt_{error}', 'texmode', 'on');" + } + System { + Name "Yaw Rate Controller Input" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "yawrate_error_model" + SID "1225" + Position [85, 158, 115, 172] + ZOrder 284 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1222" + Ports [1, 1] + Position [185, 146, 255, 184] + ZOrder 283 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 78 + $ClassName "Simulink.Mask" + Display "disp('Feedback', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "yawrate_error_model" + SID "1223" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "yawrate_error" + SID "1224" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "yawrate_error_model" + SrcPort 1 + DstBlock "yawrate_error" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "yawrate error" + SID "1098" + Ports [0, 1] + Position [185, 73, 255, 107] + ZOrder 282 + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 79 + $ClassName "Simulink.Mask" + Display "disp('d\\psi/dt_{error}', 'texmode', 'on');" + } + System { + Name "yawrate error" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "200" + Block { + BlockType FromWorkspace + Name "From\nWorkspace8" + SID "1020" + Position [15, 18, 80, 42] + ZOrder 245 + VariableName "yawrate_error" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "yawrate_error" + SID "1101" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace8" + SrcPort 1 + DstBlock "yawrate_error" + DstPort 1 + } + } } Block { BlockType Outport - Name "y" - SID "923::5" - Position [460, 101, 480, 119] - ZOrder -5 + Name "yawrate_error" + SID "1204" + Position [410, 83, 440, 97] + ZOrder -2 + ForegroundColor "magenta" IconDisplay "Port number" } - Line { - ZOrder 1 - SrcBlock "u" - SrcPort 1 - DstBlock " SFunction " + Annotation { + SID "1206" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" + "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" + "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" + " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" + "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" + "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" + "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" + "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" + "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " + "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" + "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" + "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" + "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" + "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" + "ve variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } + } + } + Block { + BlockType Outport + Name "height_controlled" + SID "606" + Position [1500, -717, 1530, -703] + ZOrder -2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "y_controlled" + SID "636" + Position [1505, -477, 1535, -463] + ZOrder 74 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "x_controlled" + SID "637" + Position [1500, -217, 1530, -203] + ZOrder 75 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "yaw_controlled" + SID "638" + Position [1495, 53, 1525, 67] + ZOrder 76 + Port "4" + IconDisplay "Port number" + } + Line { + ZOrder 48 + SrcBlock "pitch_rate" + SrcPort 1 + Points [15, 0] + Branch { + ZOrder 491 + Points [0, 55] + DstBlock "Scope6" + DstPort 1 + } + Branch { + ZOrder 229 + DstBlock "Sum4" + DstPort 2 + } + } + Line { + ZOrder 26 + SrcBlock "z_setpoint" + SrcPort 1 + DstBlock "Sum7" + DstPort 1 + } + Line { + ZOrder 31 + SrcBlock "x_position" + SrcPort 1 + Points [40, 0] + Branch { + ZOrder 839 + Points [0, 45] + Branch { + ZOrder 843 + Points [0, 60] + DstBlock "Scope4" + DstPort 1 + } + Branch { + ZOrder 842 + DstBlock "To Workspace9" + DstPort 1 + } + } + Branch { + ZOrder 237 + DstBlock "Sum5" + DstPort 2 + } + } + Line { + ZOrder 1613 + SrcBlock "PID Controller5" + SrcPort 1 + Points [15, 0] + Branch { + ZOrder 954 + DstBlock "Sum4" + DstPort 1 + } + Branch { + ZOrder 953 + Points [0, -65] + DstBlock "To Workspace1" + DstPort 1 + } + } + Line { + ZOrder 1614 + SrcBlock "PID Controller11" + SrcPort 1 + Points [17, 0] + Branch { + ZOrder 956 + DstBlock "Sum3" + DstPort 1 + } + Branch { + ZOrder 955 + Points [0, -65] + DstBlock "To Workspace" + DstPort 1 + } + } + Line { + ZOrder 43 + SrcBlock "pitch" + SrcPort 1 + Points [10, 0] + Branch { + ZOrder 492 + Points [0, 45] + DstBlock "Gain" + DstPort 1 + } + Branch { + ZOrder 490 + DstBlock "Sum3" + DstPort 2 + } + } + Line { + ZOrder 494 + SrcBlock "Gain" + SrcPort 1 + DstBlock "Scope9" + DstPort 1 + } + Line { + ZOrder 1609 + SrcBlock "PID Controller1" + SrcPort 1 + Points [260, 0] + Branch { + ZOrder 1345 + Points [0, -65] + DstBlock "To Workspace8" + DstPort 1 + } + Branch { + ZOrder 1344 + DstBlock "Saturation" + DstPort 1 + } + } + Line { + ZOrder 1611 + SrcBlock "PID Controller9" + SrcPort 1 + Points [21, 0] + Branch { + ZOrder 1274 + Points [0, -65] + DstBlock "To Workspace2" + DstPort 1 + } + Branch { + ZOrder 1273 + DstBlock "Saturation1" + DstPort 1 + } + } + Line { + ZOrder 1615 + SrcBlock "Latitude Controller Input" + SrcPort 1 + DstBlock "PID Controller11" + DstPort 1 + } + Line { + ZOrder 699 + SrcBlock "x_setpoint" + SrcPort 1 + DstBlock "Sum5" + DstPort 1 + } + Line { + ZOrder 753 + SrcBlock "roll_rate" + SrcPort 1 + Points [20, 0] + Branch { + ZOrder 719 + Points [0, 55] + DstBlock "Scope11" + DstPort 1 + } + Branch { + ZOrder 718 + DstBlock "Sum10" + DstPort 2 + } + } + Line { + ZOrder 751 + SrcBlock "y_position" + SrcPort 1 + Points [45, 0] + Branch { + ZOrder 722 + Points [0, 50] + Branch { + ZOrder 1043 + Points [0, 55] + DstBlock "Scope12" DstPort 1 } - Line { - Name "y" - ZOrder 2 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "y" + Branch { + ZOrder 845 + DstBlock "To Workspace11" DstPort 1 } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " + } + Branch { + ZOrder 721 + DstBlock "Sum11" + DstPort 2 + } + } + Line { + ZOrder 1764 + SrcBlock "PID Controller2" + SrcPort 1 + Points [25, 0] + Branch { + ZOrder 1709 + DstBlock "Sum10" + DstPort 1 + } + Branch { + ZOrder 1708 + Points [0, -60] + DstBlock "To Workspace4" + DstPort 1 + } + } + Line { + ZOrder 1616 + SrcBlock "PID Controller7" + SrcPort 1 + Points [16, 0] + Branch { + ZOrder 1713 + DstBlock "Sum9" + DstPort 1 + } + Branch { + ZOrder 1712 + Points [0, -60] + DstBlock "To Workspace3" + DstPort 1 + } + } + Line { + ZOrder 752 + SrcBlock "roll" + SrcPort 1 + Points [15, 0] + Branch { + ZOrder 731 + Points [0, 45] + DstBlock "Gain2" + DstPort 1 + } + Branch { + ZOrder 730 + DstBlock "Sum9" + DstPort 2 + } + } + Line { + ZOrder 733 + SrcBlock "Gain2" + SrcPort 1 + DstBlock "Scope13" + DstPort 1 + } + Line { + ZOrder 750 + SrcBlock "y_setpoint" + SrcPort 1 + DstBlock "Sum11" + DstPort 1 + } + Line { + ZOrder 1503 + SrcBlock "PID Controller17" + SrcPort 1 + Points [525, 0] + Branch { + ZOrder 1767 + Points [0, -80] + DstBlock "To Workspace6" + DstPort 1 + } + Branch { + ZOrder 1766 + DstBlock "Saturation3" + DstPort 1 + } + } + Line { + ZOrder 785 + SrcBlock "yaw" + SrcPort 1 + Points [25, 0] + Branch { + ZOrder 778 + Points [0, 45] + Branch { + ZOrder 1214 + Points [0, 65] + DstBlock "Scope3" DstPort 1 } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " + Branch { + ZOrder 841 + DstBlock "To Workspace10" DstPort 1 } } + Branch { + ZOrder 777 + DstBlock "Sum1" + DstPort 2 + } } - Block { - BlockType RateTransition - Name "Rate Transition" - SID "924" - Position [755, 94, 795, 136] - ZOrder -13 - NamePlacement "alternate" - OutPortSampleTime "0.06" + Line { + ZOrder 784 + SrcBlock "yaw_setpoint" + SrcPort 1 + DstBlock "Sum1" + DstPort 1 } - Block { - BlockType RateTransition - Name "Rate Transition1" - SID "925" - Position [735, 210, 770, 250] - ZOrder -14 - OutPortSampleTime "0.06" + Line { + ZOrder 810 + SrcBlock "yaw_rate" + SrcPort 1 + Points [25, 0] + Branch { + ZOrder 822 + Points [0, 25] + DstBlock "Gain1" + DstPort 1 + } + Branch { + ZOrder 821 + DstBlock "Sum2" + DstPort 2 + } } - Block { - BlockType Reference - Name "VR Sink" - SID "926" - Ports [2] - Position [865, 76, 1055, 234] - ZOrder -15 - LibraryVersion "1.36" - SourceBlock "vrlib/VR Sink" - SourceType "Virtual Reality Sink" - InstantiateOnLoad on - SampleTime "-1" - ViewEnable on - RemoteChange off - RemoteView off - FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" - WorldFileName "quadrotor_world_ucart.wrl" - AutoView on - VideoDimensions "[]" - AllowVariableSize off + Line { + ZOrder 806 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "Scope1" + DstPort 1 } Line { - ZOrder 1 - SrcBlock "Displacement" + ZOrder 1501 + SrcBlock "PID Controller4" SrcPort 1 - DstBlock "Demux" + Points [11, 0] + Branch { + ZOrder 1591 + DstBlock "Sum2" + DstPort 1 + } + Branch { + ZOrder 1590 + Points [0, -65] + DstBlock "To Workspace7" + DstPort 1 + } + } + Line { + ZOrder 34 + SrcBlock "z_position" + SrcPort 1 + Points [30, 0] + Branch { + ZOrder 108 + Points [0, 30] + Branch { + ZOrder 849 + DstBlock "To Workspace12" + DstPort 1 + } + Branch { + ZOrder 848 + Points [0, 50] + DstBlock "Scope2" + DstPort 1 + } + } + Branch { + ZOrder 107 + DstBlock "Sum7" + DstPort 2 + } + } + Line { + ZOrder 1163 + SrcBlock "Sum1" + SrcPort 1 + DstBlock "Yaw Controller Input" DstPort 1 } Line { - ZOrder 2 - SrcBlock "Bus\nCreator2" + ZOrder 1500 + SrcBlock "Yaw Controller Input" SrcPort 1 - DstBlock "Bus\nSelector" + DstBlock "PID Controller4" DstPort 1 } Line { - ZOrder 3 - SrcBlock "Demux" + ZOrder 1190 + SrcBlock "Sum2" SrcPort 1 - Points [40, 0; 0, 40; 120, 0] - DstBlock "Bus\nCreator1" - DstPort 3 + DstBlock "Yaw Rate Controller Input" + DstPort 1 } Line { - ZOrder 4 - SrcBlock "Gain" + ZOrder 1608 + SrcBlock "Yaw Rate Controller Input" SrcPort 1 - Points [5, 0; 0, -25] - DstBlock "Bus\nCreator1" - DstPort 2 + DstBlock "PID Controller1" + DstPort 1 } Line { - ZOrder 5 - SrcBlock "Gain2" + ZOrder 1194 + SrcBlock "Sum5" SrcPort 1 - DstBlock "Bus\nCreator1" + DstBlock "Latitude Controller Input" DstPort 1 } Line { - ZOrder 6 - SrcBlock "Rate Transition1" + ZOrder 1195 + SrcBlock "Sum3" SrcPort 1 - Points [35, 0; 0, -35] - DstBlock "VR Sink" - DstPort 2 + DstBlock "Pitch Controller Input" + DstPort 1 } Line { - ZOrder 7 - SrcBlock "Rate Transition" + ZOrder 1612 + SrcBlock "Pitch Controller Input" SrcPort 1 - DstBlock "VR Sink" + DstBlock "PID Controller5" DstPort 1 } Line { - ZOrder 8 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Gain" + ZOrder 1197 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "Pitch Rate Controller Input" DstPort 1 } Line { - ZOrder 9 - SrcBlock "Demux" - SrcPort 2 - Points [80, 0] - DstBlock "Gain2" + ZOrder 1610 + SrcBlock "Pitch Rate Controller Input" + SrcPort 1 + DstBlock "PID Controller9" DstPort 1 } Line { - ZOrder 10 - SrcBlock "Bus\nCreator1" + ZOrder 1199 + SrcBlock "Sum11" SrcPort 1 - DstBlock "Gain1" + DstBlock "Longitude Controller Input" DstPort 1 } Line { - Name "<phi>" - ZOrder 11 - Labels [0, 0] - SrcBlock "Bus\nSelector" + ZOrder 1617 + SrcBlock "Longitude Controller Input" SrcPort 1 - Points [0, -10; 45, 0; 0, 60] - DstBlock "Bus\nCreator" - DstPort 3 + DstBlock "PID Controller7" + DstPort 1 } Line { - Name "<psi>" - ZOrder 12 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 3 - Points [0, -10; 75, 0] - DstBlock "Bus\nCreator" - DstPort 2 + ZOrder 1201 + SrcBlock "Sum9" + SrcPort 1 + DstBlock "Roll Controller Input" + DstPort 1 } Line { - Name "<theta>" - ZOrder 13 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 2 - Points [30, 0; 0, -25] - DstBlock "Bus\nCreator" + ZOrder 1765 + SrcBlock "Roll Controller Input" + SrcPort 1 + DstBlock "PID Controller2" DstPort 1 } Line { - ZOrder 14 - SrcBlock "Gain1" + ZOrder 1204 + SrcBlock "Sum10" SrcPort 1 - DstBlock "Rate Transition1" + DstBlock "Roll Rate Controller Input" DstPort 1 } Line { - Name "psi" - ZOrder 15 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Bus\nCreator2" - DstPort 3 + ZOrder 1502 + SrcBlock "Altitude Controller Input" + SrcPort 1 + DstBlock "PID Controller17" + DstPort 1 } Line { - Name "theta" - ZOrder 16 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Bus\nCreator2" - DstPort 2 + ZOrder 1210 + SrcBlock "Sum7" + SrcPort 1 + DstBlock "Altitude Controller Input" + DstPort 1 } Line { - Name "phi" - ZOrder 17 - Labels [0, 0] - SrcBlock "Demux1" + ZOrder 1763 + SrcBlock "Roll Rate Controller Input" SrcPort 1 - DstBlock "Bus\nCreator2" + DstBlock "PID Controller3" DstPort 1 } Line { - ZOrder 18 - SrcBlock "Euler Angles" + ZOrder 1762 + SrcBlock "PID Controller3" SrcPort 1 - DstBlock "Demux1" + Points [16, 0] + Branch { + ZOrder 1602 + Points [0, -60] + DstBlock "To Workspace5" + DstPort 1 + } + Branch { + ZOrder 1601 + DstBlock "Saturation2" + DstPort 1 + } + } + Line { + ZOrder 1701 + SrcBlock "Saturation2" + SrcPort 1 + DstBlock "y_controlled" DstPort 1 } Line { - ZOrder 19 - SrcBlock "Bus\nCreator" + ZOrder 1716 + SrcBlock "Saturation1" SrcPort 1 - DstBlock "MATLAB Function" + DstBlock "x_controlled" DstPort 1 } Line { - ZOrder 20 - SrcBlock "MATLAB Function" + ZOrder 1768 + SrcBlock "Saturation" SrcPort 1 - DstBlock "Rate Transition" + DstBlock "yaw_controlled" DstPort 1 } } } + Block { + BlockType Reference + Name "Counter\nFree-Running" + SID "899" + Ports [0, 1] + Position [275, 955, 305, 985] + ZOrder 59 + LibraryVersion "1.388" + SourceBlock "simulink/Sources/Counter\nFree-Running" + SourceType "Counter Free-Running" + ContentPreviewEnabled off + NumBits "32" + tsamp "Tc" + } + Block { + BlockType Demux + Name "Demux" + SID "586" + Ports [1, 4] + Position [300, 319, 305, 416] + ZOrder 13 + ShowName off + DisplayOption "bar" + } + Block { + BlockType Demux + Name "Demux1" + SID "639" + Ports [1, 3] + Position [300, 494, 305, 566] + ZOrder 32 + ShowName off + Outputs "3" + DisplayOption "bar" + } + Block { + BlockType Demux + Name "Demux2" + SID "588" + Ports [1, 3] + Position [285, 419, 290, 491] + ZOrder 15 + ShowName off + Outputs "3" + DisplayOption "bar" + } + Block { + BlockType Demux + Name "Demux3" + SID "1422" + Ports [1, 4] + Position [1650, 511, 1655, 549] + ZOrder 321 + ShowName off + DisplayOption "bar" + } + Block { + BlockType Demux + Name "Demux4" + SID "640" + Ports [1, 3] + Position [275, 569, 280, 641] + ZOrder 33 + ShowName off + Outputs "3" + DisplayOption "bar" + } Block { BlockType SubSystem - Name "3D Graphical Simulation1" - SID "936" - Ports [2] - Position [2635, 815, 2785, 875] - ZOrder 290 + Name "MATLAB Function1" + SID "887" + Ports [15, 6] + Position [390, 687, 530, 1013] + ZOrder 47 + Commented "on" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + SystemSampleTime "Tq" RequestExecContextInheritance off + SFBlockType "MATLAB Function" Variant off Object { $PropName "MaskObject" - $ObjectID 39 + $ObjectID 80 $ClassName "Simulink.Mask" - Display "port_label('input',1, '\\Theta','texmode','on')\nport_label('input',2,'r_{o}','texmode','on')" + Display "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se" + "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', " + "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'" + ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\" + "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't" + "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '" + "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('input', 14, 'VRPN ID', 'tex" + "mode', 'on');\nport_label('input', 15, '\\tau_c', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode', 'o" + "n');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\nport_la" + "bel('output', 4, 'u_R', 'texmode', 'on');\nport_label('output', 5, 'PID y out', 'texmode', 'on');\nport_label('ou" + "tput', 6, 'PID roll out', 'texmode', 'on');\ndisp('C Controller', 'texmode', 'on');" } System { - Name "3D Graphical Simulation1" - Location [-8, -8, 1928, 1048] + Name "MATLAB Function1" + Location [223, 338, 826, 833] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -5281,687 +12455,647 @@ Model { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "80" + ZoomFactor "100" + SIDHighWatermark "41" Block { BlockType Inport - Name "Euler Angles\n" - SID "937" - Position [180, 108, 210, 122] + Name "set_x" + SID "887::1" + Position [20, 101, 40, 119] ZOrder -1 IconDisplay "Port number" } Block { BlockType Inport - Name "Displacement" - SID "938" - Position [180, 218, 210, 232] - ZOrder -2 + Name "set_y" + SID "887::22" + Position [20, 136, 40, 154] + ZOrder 13 Port "2" IconDisplay "Port number" } Block { - BlockType BusCreator - Name "Bus\nCreator" - SID "939" - Ports [3, 1] - Position [600, 76, 610, 154] - ZOrder -3 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on + BlockType Inport + Name "set_z" + SID "887::23" + Position [20, 171, 40, 189] + ZOrder 14 + Port "3" + IconDisplay "Port number" } Block { - BlockType BusCreator - Name "Bus\nCreator1" - SID "940" - Ports [3, 1] - Position [630, 191, 640, 269] - ZOrder -4 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on + BlockType Inport + Name "set_yaw" + SID "887::24" + Position [20, 206, 40, 224] + ZOrder 15 + Port "4" + IconDisplay "Port number" } Block { - BlockType BusCreator - Name "Bus\nCreator2" - SID "941" - Ports [3, 1] - Position [385, 75, 390, 155] - ZOrder -5 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on + BlockType Inport + Name "cur_x" + SID "887::25" + Position [20, 246, 40, 264] + ZOrder 16 + Port "5" + IconDisplay "Port number" } Block { - BlockType BusSelector - Name "Bus\nSelector" - SID "942" - Ports [1, 3] - Position [500, 77, 505, 153] - ZOrder -6 - ShowName off - OutputSignals "phi,theta,psi" - Port { - PortNumber 1 - Name "<phi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "<theta>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "<psi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } + BlockType Inport + Name "cur_y" + SID "887::26" + Position [20, 281, 40, 299] + ZOrder 17 + Port "6" + IconDisplay "Port number" } Block { - BlockType Demux - Name "Demux" - SID "943" - Ports [1, 3] - Position [440, 183, 450, 267] - ZOrder -7 - BackgroundColor "black" - ShowName off - Outputs "3" - DisplayOption "bar" + BlockType Inport + Name "cur_z" + SID "887::27" + Position [20, 316, 40, 334] + ZOrder 18 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "cur_phi" + SID "887::28" + Position [20, 351, 40, 369] + ZOrder 19 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "cur_theta" + SID "887::29" + Position [20, 386, 40, 404] + ZOrder 20 + Port "9" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "cur_psi" + SID "887::30" + Position [20, 426, 40, 444] + ZOrder 21 + Port "10" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "cur_phi_d" + SID "887::31" + Position [20, 461, 40, 479] + ZOrder 22 + Port "11" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "cur_theta_d" + SID "887::32" + Position [20, 496, 40, 514] + ZOrder 23 + Port "12" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "cur_psi_d" + SID "887::33" + Position [20, 531, 40, 549] + ZOrder 24 + Port "13" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "vrpn_id" + SID "887::37" + Position [20, 566, 40, 584] + ZOrder 28 + Port "14" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Tc" + SID "887::41" + Position [20, 606, 40, 624] + ZOrder 31 + Port "15" + IconDisplay "Port number" } Block { BlockType Demux - Name "Demux1" - SID "944" - Ports [1, 3] - Position [290, 75, 295, 155] - ZOrder -8 - ShowName off - Outputs "3" - DisplayOption "bar" + Name " Demux " + SID "887::20" + Ports [1, 1] + Position [270, 350, 320, 390] + ZOrder 11 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "887::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 15" + Ports [15, 7] + Position [180, 110, 230, 430] + ZOrder 10 + FunctionName "sf_sfun" + PortCounts "[15 7]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "z_corr" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } Port { - PortNumber 1 - Name "phi" + PortNumber 3 + Name "y_cor" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } Port { - PortNumber 2 - Name "theta" + PortNumber 4 + Name "x_corr" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } Port { - PortNumber 3 - Name "psi" + PortNumber 5 + Name "yaw_corr" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 6 + Name "pid_y_out" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 7 + Name "pid_roll_out" RTWStorageClass "Auto" DataLoggingNameMode "SignalName" } } Block { - BlockType Gain - Name "Gain" - SID "945" - Position [550, 240, 580, 270] - ZOrder -10 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + BlockType Terminator + Name " Terminator " + SID "887::21" + Position [460, 361, 480, 379] + ZOrder 12 } Block { - BlockType Gain - Name "Gain1" - SID "946" - Position [670, 208, 710, 252] - ZOrder -11 - Gain "eye(3)*1" - Multiplication "Matrix(K*u)" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + BlockType Outport + Name "z_corr" + SID "887::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" } Block { - BlockType Gain - Name "Gain2" - SID "947" - Position [550, 190, 580, 220] - ZOrder -12 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off + BlockType Outport + Name "y_cor" + SID "887::34" + Position [460, 136, 480, 154] + ZOrder 25 + Port "2" + IconDisplay "Port number" } Block { - BlockType SubSystem - Name "MATLAB Function" - SID "948" - Ports [1, 1] - Position [655, 92, 725, 138] - ZOrder 5 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - System { - Name "MATLAB Function" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "21" - Block { - BlockType Inport - Name "u" - SID "948::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "948::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "948::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 3" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[1 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "y" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "948::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "y" - SID "948::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "u" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "y" - ZOrder 2 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "y" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } + BlockType Outport + Name "x_corr" + SID "887::35" + Position [460, 171, 480, 189] + ZOrder 26 + Port "3" + IconDisplay "Port number" } Block { - BlockType RateTransition - Name "Rate Transition" - SID "949" - Position [755, 94, 795, 136] - ZOrder -13 - NamePlacement "alternate" - OutPortSampleTime "0.06" + BlockType Outport + Name "yaw_corr" + SID "887::36" + Position [460, 206, 480, 224] + ZOrder 27 + Port "4" + IconDisplay "Port number" } Block { - BlockType RateTransition - Name "Rate Transition1" - SID "950" - Position [735, 210, 770, 250] - ZOrder -14 - OutPortSampleTime "0.06" + BlockType Outport + Name "pid_y_out" + SID "887::38" + Position [460, 246, 480, 264] + ZOrder 29 + Port "5" + IconDisplay "Port number" } Block { - BlockType Reference - Name "VR Sink" - SID "951" - Ports [2] - Position [865, 76, 1055, 234] - ZOrder -15 - LibraryVersion "1.36" - SourceBlock "vrlib/VR Sink" - SourceType "Virtual Reality Sink" - InstantiateOnLoad on - SampleTime "-1" - ViewEnable on - RemoteChange off - RemoteView off - FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" - WorldFileName "quadrotor_world_ucart.wrl" - AutoView on - VideoDimensions "[]" - AllowVariableSize off + BlockType Outport + Name "pid_roll_out" + SID "887::39" + Position [460, 281, 480, 299] + ZOrder 30 + Port "6" + IconDisplay "Port number" } Line { - ZOrder 2 - SrcBlock "Bus\nCreator2" + ZOrder 319 + SrcBlock "set_x" SrcPort 1 - DstBlock "Bus\nSelector" + DstBlock " SFunction " DstPort 1 } Line { - ZOrder 3 - SrcBlock "Demux" + ZOrder 320 + SrcBlock "set_y" SrcPort 1 - Points [40, 0; 0, 40; 120, 0] - DstBlock "Bus\nCreator1" + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 321 + SrcBlock "set_z" + SrcPort 1 + DstBlock " SFunction " DstPort 3 } Line { - ZOrder 4 - SrcBlock "Gain" + ZOrder 322 + SrcBlock "set_yaw" SrcPort 1 - Points [5, 0; 0, -25] - DstBlock "Bus\nCreator1" - DstPort 2 + DstBlock " SFunction " + DstPort 4 } Line { - ZOrder 5 - SrcBlock "Gain2" + ZOrder 323 + SrcBlock "cur_x" SrcPort 1 - DstBlock "Bus\nCreator1" - DstPort 1 + DstBlock " SFunction " + DstPort 5 } Line { - ZOrder 6 - SrcBlock "Rate Transition1" + ZOrder 324 + SrcBlock "cur_y" SrcPort 1 - Points [35, 0; 0, -35] - DstBlock "VR Sink" - DstPort 2 + DstBlock " SFunction " + DstPort 6 } Line { - ZOrder 7 - SrcBlock "Rate Transition" + ZOrder 325 + SrcBlock "cur_z" SrcPort 1 - DstBlock "VR Sink" - DstPort 1 + DstBlock " SFunction " + DstPort 7 + } + Line { + ZOrder 326 + SrcBlock "cur_phi" + SrcPort 1 + DstBlock " SFunction " + DstPort 8 + } + Line { + ZOrder 327 + SrcBlock "cur_theta" + SrcPort 1 + DstBlock " SFunction " + DstPort 9 + } + Line { + ZOrder 328 + SrcBlock "cur_psi" + SrcPort 1 + DstBlock " SFunction " + DstPort 10 } Line { - ZOrder 8 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Gain" - DstPort 1 + ZOrder 329 + SrcBlock "cur_phi_d" + SrcPort 1 + DstBlock " SFunction " + DstPort 11 } Line { - ZOrder 9 - SrcBlock "Demux" - SrcPort 2 - Points [80, 0] - DstBlock "Gain2" - DstPort 1 + ZOrder 330 + SrcBlock "cur_theta_d" + SrcPort 1 + DstBlock " SFunction " + DstPort 12 } Line { - ZOrder 10 - SrcBlock "Bus\nCreator1" + ZOrder 331 + SrcBlock "cur_psi_d" SrcPort 1 - DstBlock "Gain1" - DstPort 1 + DstBlock " SFunction " + DstPort 13 } Line { - Name "<phi>" - ZOrder 11 - Labels [0, 0] - SrcBlock "Bus\nSelector" + ZOrder 332 + SrcBlock "vrpn_id" SrcPort 1 - Points [0, -10; 45, 0; 0, 60] - DstBlock "Bus\nCreator" - DstPort 3 + DstBlock " SFunction " + DstPort 14 } Line { - Name "<psi>" - ZOrder 12 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 3 - Points [0, -10; 75, 0] - DstBlock "Bus\nCreator" - DstPort 2 + ZOrder 333 + SrcBlock "Tc" + SrcPort 1 + DstBlock " SFunction " + DstPort 15 } Line { - Name "<theta>" - ZOrder 13 + Name "z_corr" + ZOrder 334 Labels [0, 0] - SrcBlock "Bus\nSelector" + SrcBlock " SFunction " SrcPort 2 - Points [30, 0; 0, -25] - DstBlock "Bus\nCreator" - DstPort 1 - } - Line { - ZOrder 14 - SrcBlock "Gain1" - SrcPort 1 - DstBlock "Rate Transition1" + DstBlock "z_corr" DstPort 1 } Line { - Name "psi" - ZOrder 15 + Name "y_cor" + ZOrder 335 Labels [0, 0] - SrcBlock "Demux1" + SrcBlock " SFunction " SrcPort 3 - DstBlock "Bus\nCreator2" - DstPort 3 + DstBlock "y_cor" + DstPort 1 } Line { - Name "theta" - ZOrder 16 + Name "x_corr" + ZOrder 336 Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Bus\nCreator2" - DstPort 2 + SrcBlock " SFunction " + SrcPort 4 + DstBlock "x_corr" + DstPort 1 } Line { - Name "phi" - ZOrder 17 + Name "yaw_corr" + ZOrder 337 Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Bus\nCreator2" + SrcBlock " SFunction " + SrcPort 5 + DstBlock "yaw_corr" DstPort 1 } Line { - ZOrder 19 - SrcBlock "Bus\nCreator" - SrcPort 1 - DstBlock "MATLAB Function" + Name "pid_y_out" + ZOrder 338 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 6 + DstBlock "pid_y_out" DstPort 1 } Line { - ZOrder 20 - SrcBlock "MATLAB Function" - SrcPort 1 - DstBlock "Rate Transition" + Name "pid_roll_out" + ZOrder 339 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 7 + DstBlock "pid_roll_out" DstPort 1 } Line { - ZOrder 21 - SrcBlock "Displacement" + ZOrder 340 + SrcBlock " Demux " SrcPort 1 - DstBlock "Demux" + DstBlock " Terminator " DstPort 1 } Line { - ZOrder 22 - SrcBlock "Euler Angles\n" + ZOrder 341 + SrcBlock " SFunction " SrcPort 1 - DstBlock "Demux1" + DstBlock " Demux " DstPort 1 } } } Block { - BlockType Delay - Name "Delay" - SID "910" - Ports [1, 1] - Position [2090, 843, 2125, 877] - ZOrder 286 - BlockMirror on - InputPortMap "u0" - DelayLength "1" - InitialCondition "0" - } - Block { - BlockType Delay - Name "Delay1" - SID "909" - Ports [1, 1] - Position [1660, 638, 1695, 672] - ZOrder 285 - BlockMirror on - InputPortMap "u0" - DelayLength "1" - InitialCondition "0" - } - Block { - BlockType Demux - Name "Demux" - SID "984" - Ports [1, 3] - Position [1810, 1023, 1815, 1077] - ZOrder 294 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "1006" - Ports [1, 2] - Position [2280, 605, 2285, 660] - ZOrder 300 - ShowName off - Outputs "2" - DisplayOption "bar" - } - Block { - BlockType Reference - Name "First-Order\nHold" - SID "953" - Ports [1, 1] - Position [2530, 780, 2565, 810] - ZOrder 292 - LibraryVersion "1.388" - DisableCoverage on - SourceBlock "simulink/Discrete/First-Order\nHold" - SourceType "First-Order Hold" - ContentPreviewEnabled off - Ts "6.1e-3" - } - Block { - BlockType Reference - Name "First-Order\nHold1" - SID "986" + BlockType SubSystem + Name "Motor Commands" + SID "1409" Ports [1, 1] - Position [2530, 875, 2565, 905] - ZOrder 296 - LibraryVersion "1.388" - DisableCoverage on - SourceBlock "simulink/Discrete/First-Order\nHold" - SourceType "First-Order Hold" - ContentPreviewEnabled off - Ts "6.1e-3" - } - Block { - BlockType Mux - Name "Mux" - SID "1007" - Ports [3, 1] - Position [2455, 608, 2460, 682] - ZOrder 301 + Position [1400, 457, 1555, 503] + ZOrder 319 + ForegroundColor "magenta" ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType Scope - Name "Scope" - SID "894" - Ports [1] - Position [1385, 669, 1415, 701] - ZOrder 270 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -10 - YMax 10 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [680 330 1240 750] - } - Block { - BlockType Scope - Name "Scope1" - SID "895" - Ports [1] - Position [1385, 599, 1415, 631] - ZOrder 271 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -1.18227 - YMax 0.1338 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" + RequestExecContextInheritance off + Variant on + Object { + $PropName "MaskObject" + $ObjectID 81 + $ClassName "Simulink.Mask" + Display "disp('Motor Commands', 'texmode', 'on');" } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" + System { + Name "Motor Commands" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "175" + Block { + BlockType Inport + Name "z_command_model" + SID "1410" + Position [85, 118, 115, 132] + ZOrder 288 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1411" + Ports [1, 1] + Position [185, 153, 345, 187] + ZOrder 287 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 82 + $ClassName "Simulink.Mask" + Display "disp('Motor Command from Model', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "z_command_model" + SID "1412" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "z_command" + SID "1413" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "z_command_model" + SrcPort 1 + DstBlock "z_command" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Motor Command" + SID "1414" + Ports [0, 1] + Position [210, 75, 320, 105] + ZOrder 279 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 83 + $ClassName "Simulink.Mask" + Display "disp('Motor Command', 'texmode', 'on');" + } + System { + Name "Motor Command" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "125" + Block { + BlockType FromWorkspace + Name "From\nWorkspace5" + SID "1415" + Position [-35, 17, 80, 43] + ZOrder 210 + VariableName "motor_commands" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "z_command" + SID "1416" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace5" + SrcPort 1 + DstBlock "z_command" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "z_command" + SID "1417" + Position [410, 118, 440, 132] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1418" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" + "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" + "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" + "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" + "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" + "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" + "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" + "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" + "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" + "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" + "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" + "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" + "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" + "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" + "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 + } } - Location [1 76 1921 1039] } Block { - BlockType Scope - Name "Scope3" - SID "897" - Ports [1] - Position [2255, 534, 2285, 566] - ZOrder 278 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData4 - YMin -1.66746 - YMax 0.20394 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat Array - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] + BlockType Saturate + Name "Saturation" + SID "756" + Ports [1, 1] + Position [1270, 465, 1300, 495] + ZOrder 44 + InputPortMap "u0" + UpperLimit "Pmax*ones(4,1)" + LowerLimit "Pmin*ones(4,1)" } Block { BlockType Scope - Name "Scope6" - SID "898" - Ports [1] - Position [1955, 469, 1985, 501] - ZOrder 280 - NumInputPorts "1" + Name "Scope" + SID "1421" + Ports [4] + Position [1705, 514, 1735, 546] + ZOrder 320 + NumInputPorts "4" Open off TimeRange auto TickLabels OneTimeTick @@ -5969,9 +13103,9 @@ Model { LimitDataPoints off MaxDataPoints 5000 SaveToWorkspace off - SaveName ScopeData5 - YMin -0.10821 - YMax 0.91739 + SaveName ScopeData1 + YMin 127563.375~120690.00000~120652.25~129711.75 + YMax 167209.625~181750.00000~182389.75~170414.25 SampleInput off SampleTime -1 ZoomMode on @@ -5981,6 +13115,9 @@ Model { List { ListType AxesTitles axes1 "%<SignalLabel>" + axes2 "%<SignalLabel>" + axes3 "%<SignalLabel>" + axes4 "%<SignalLabel>" } List { ListType ScopeGraphics @@ -5992,721 +13129,1365 @@ Model { LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" MarkerStyles "none|none|none|none|none|none" } - Location [1 76 1921 1039] + Location [962 84 1920 1038] } Block { - BlockType Scope - Name "Scope7" - SID "899" - Ports [1] - Position [1955, 544, 1985, 576] - ZOrder 281 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData6 - YMin -2.66218 - YMax 0.34207 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" + BlockType SubSystem + Name "Signal Mixer" + SID "647" + Ports [4, 1] + Position [960, 320, 1220, 640] + ZOrder 35 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + Object { + $PropName "MaskObject" + $ObjectID 84 + $ClassName "Simulink.Mask" + Display "port_label('input', 1, 'u_T', 'texmode', 'on');\nport_label('input', 2, 'u_A', 'texmode', 'on');\np" + "ort_label('input', 3, 'u_E', 'texmode', 'on');\nport_label('input', 4, 'u_R', 'texmode', 'on');\nport_label('outp" + "ut', 1, 'P', 'texmode', 'on');\ndisp('Signal Mixer', 'texmode', 'on');" } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" + System { + Name "Signal Mixer" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "27" + Block { + BlockType Inport + Name "height_controlled" + SID "647::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "y_controlled" + SID "647::23" + Position [20, 136, 40, 154] + ZOrder 14 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "x_controlled" + SID "647::22" + Position [20, 171, 40, 189] + ZOrder 13 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "yaw_controlled" + SID "647::24" + Position [20, 206, 40, 224] + ZOrder 15 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "647::20" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 11 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "647::19" + Tag "Stateflow S-Function Quadcopter_Model_R2015_A 14" + Ports [4, 2] + Position [180, 107, 230, 208] + ZOrder 10 + FunctionName "sf_sfun" + PortCounts "[4 2]" + SFunctionDeploymentMode off + EnableBusSupport on + Port { + PortNumber 2 + Name "P" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "647::21" + Position [460, 241, 480, 259] + ZOrder 12 + } + Block { + BlockType Outport + Name "P" + SID "647::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 105 + SrcBlock "height_controlled" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 106 + SrcBlock "y_controlled" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 107 + SrcBlock "x_controlled" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 108 + SrcBlock "yaw_controlled" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + Name "P" + ZOrder 109 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "P" + DstPort 1 + } + Line { + ZOrder 110 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 111 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } } - Location [1 76 1909 1039] } Block { - BlockType S-Function - Name "Soft Real Time" - SID "927" - Ports [] - Position [2033, 1185, 2120, 1216] - ZOrder 288 + BlockType Sum + Name "Sum" + SID "748" + Ports [2, 1] + Position [665, 350, 685, 370] + ZOrder 36 ShowName off - Commented "on" - FunctionName "sfun_time" - Parameters "x" - SFunctionDeploymentMode off - EnableBusSupport off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum1" + SID "749" + Ports [2, 1] + Position [665, 430, 685, 450] + ZOrder 37 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum2" + SID "750" + Ports [2, 1] + Position [665, 510, 685, 530] + ZOrder 38 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "751" + Ports [2, 1] + Position [665, 590, 685, 610] + ZOrder 39 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType SubSystem + Name "Throttle Command Input" + SID "1278" + Ports [1, 1] + Position [740, 337, 895, 383] + ZOrder 318 + ForegroundColor "magenta" + ShowName off + RequestExecContextInheritance off + Variant on Object { $PropName "MaskObject" - $ObjectID 40 + $ObjectID 85 $ClassName "Simulink.Mask" - Display "color('red')\ndisp('Soft Real Time')\n" - Object { - $PropName "Parameters" - $ObjectID 41 - $ClassName "Simulink.MaskParameter" - Type "edit" - Name "x" - Prompt "Time Scaling Factor" - Value "1" + Display "disp('Throttle Command', 'texmode', 'on');" + } + System { + Name "Throttle Command Input" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "175" + Block { + BlockType Inport + Name "z_command_model" + SID "1279" + Position [85, 118, 115, 132] + ZOrder 288 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Feedback" + SID "1280" + Ports [1, 1] + Position [185, 153, 345, 187] + ZOrder 287 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==0" + Object { + $PropName "MaskObject" + $ObjectID 86 + $ClassName "Simulink.Mask" + Display "disp('Throttle Command from Model', 'texmode', 'on');" + } + System { + Name "Feedback" + Location [-7, -7, 1288, 688] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "z_command_model" + SID "1281" + Position [105, 103, 135, 117] + ZOrder 2 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "z_command" + SID "1282" + Position [360, 103, 390, 117] + ZOrder -2 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "z_command_model" + SrcPort 1 + DstBlock "z_command" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Throttle Command" + SID "1283" + Ports [0, 1] + Position [210, 75, 320, 105] + ZOrder 279 + ShowName off + RequestExecContextInheritance off + Variant off + VariantControl "logAnalysisToggle==1" + Object { + $PropName "MaskObject" + $ObjectID 87 + $ClassName "Simulink.Mask" + Display "disp('Throttle Command', 'texmode', 'on');" + } + System { + Name "Throttle Command" + Location [-8, -8, 1928, 1048] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "175" + Block { + BlockType FromWorkspace + Name "From\nWorkspace5" + SID "1284" + Position [-35, 17, 80, 43] + ZOrder 210 + VariableName "throttle_command" + SampleTime "Tq" + ZeroCross on + } + Block { + BlockType Outport + Name "z_command" + SID "1285" + Position [145, 23, 175, 37] + ZOrder 172 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "From\nWorkspace5" + SrcPort 1 + DstBlock "z_command" + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "z_command" + SID "1286" + Position [410, 118, 440, 132] + ZOrder -2 + ForegroundColor "magenta" + IconDisplay "Port number" + } + Annotation { + SID "1287" + Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" + "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" + "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" + "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" + "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" + "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" + "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" + "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" + "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" + "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" + "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" + "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" + "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" + "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" + "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" + Tag "VSSAddChoiceText" + Position [71, 28, 448, 69] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + Interpreter "rich" + ZOrder -1 } } } Block { - BlockType Outport - Name "euler_angles_filtered" - SID "901" - Position [2540, 638, 2570, 652] - ZOrder 262 - IconDisplay "Port number" + BlockType ToWorkspace + Name "To Workspace3" + SID "1207" + Ports [1] + Position [1445, 380, 1555, 410] + ZOrder 228 + ShowName off + VariableName "motorCommands" + MaxDataPoints "inf" + SaveFormat "Structure With Time" + Save2DSignal "3-D array (concatenate along third dimension)" + FixptAsFi on + SampleTime "Tq" } Block { - BlockType Outport - Name "euler_rates" - SID "904" - Position [2005, 903, 2035, 917] - ZOrder 259 - Port "2" - IconDisplay "Port number" + BlockType Constant + Name "height_controlled_o" + SID "752" + Position [615, 380, 645, 410] + ZOrder 40 + Value "height_controlled_o" + SampleTime "Tc" + } + Block { + BlockType Constant + Name "x_controlled_o" + SID "754" + Position [615, 545, 645, 575] + ZOrder 42 + Value "x_controlled_o" + } + Block { + BlockType Constant + Name "y_controlled_o" + SID "753" + Position [615, 465, 645, 495] + ZOrder 41 + Value "y_controlled_o" + } + Block { + BlockType Constant + Name "yaw_controlled_o" + SID "755" + Position [615, 630, 645, 660] + ZOrder 43 + Value "yaw_controlled_o" } Block { BlockType Outport - Name "current_position" - SID "928" - Position [2335, 963, 2365, 977] - ZOrder 289 - Port "3" + Name "P" + SID "578" + Position [1665, 473, 1695, 487] + ZOrder -2 IconDisplay "Port number" } Line { - ZOrder 170 - SrcBlock "\n\n\n\n\n\n\n\n\n\n" + ZOrder 1 + SrcBlock "setpoints" SrcPort 1 - Points [23, 0] - Branch { - ZOrder 199 - Points [0, -70] - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n1" - DstPort 1 - } - Branch { - ZOrder 198 - Points [0, 25] - DstBlock "Scope1" - DstPort 1 - } + DstBlock "Demux" + DstPort 1 } Line { - ZOrder 173 - SrcBlock "\n\n\n\n\n\n\n\n\n\n" - SrcPort 2 - Points [15, 0] - Branch { - ZOrder 172 - Points [0, -35] - DstBlock "Scope" - DstPort 1 - } - Branch { - ZOrder 171 - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } + ZOrder 30 + SrcBlock "euler_angles_filtered" + SrcPort 1 + DstBlock "Demux1" + DstPort 1 } Line { - ZOrder 174 - SrcBlock "B_vo_dot" + ZOrder 3 + SrcBlock "current_position" SrcPort 1 - DstBlock "\n\n\n\n\n\n\n\n\n\n" + DstBlock "Demux2" DstPort 1 } Line { - ZOrder 175 - SrcBlock "B_vo" + ZOrder 34 + SrcBlock "euler_rates" SrcPort 1 - DstBlock "\n\n\n\n\n\n\n\n\n\n" - DstPort 2 + DstBlock "Demux4" + DstPort 1 } Line { - ZOrder 176 - SrcBlock "B_Omega" + ZOrder 27 + SrcBlock "Demux" SrcPort 1 - DstBlock "\n\n\n\n\n\n\n\n\n\n" + DstBlock "Controller" + DstPort 1 + } + Line { + ZOrder 28 + SrcBlock "Demux" + SrcPort 2 + DstBlock "Controller" + DstPort 2 + } + Line { + ZOrder 29 + SrcBlock "Demux" + SrcPort 3 + DstBlock "Controller" DstPort 3 } Line { - ZOrder 177 - SrcBlock "B_g" + ZOrder 40 + SrcBlock "Demux2" SrcPort 1 - DstBlock "\n\n\n\n\n\n\n\n\n\n" - DstPort 4 + DstBlock "Controller" + DstPort 5 } Line { - ZOrder 197 - SrcBlock "\n\n\n\n\n\n\n\n\n\n\n\n1" + ZOrder 41 + SrcBlock "Demux2" SrcPort 2 - Points [17, 0] - Branch { - ZOrder 207 - Points [0, 60] - DstBlock "Delay1" - DstPort 1 - } - Branch { - ZOrder 202 - Points [31, 0] - Branch { - ZOrder 201 - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 2 - } - Branch { - ZOrder 180 - Points [0, -35] - DstBlock "Scope7" - DstPort 1 - } - } + DstBlock "Controller" + DstPort 6 } Line { - ZOrder 195 - SrcBlock "\n\n\n\n\n\n\n\n\n\n\n\n1" - SrcPort 1 - Points [47, 0] - Branch { - ZOrder 205 - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 1 - } - Branch { - ZOrder 183 - Points [0, -35] - DstBlock "Scope6" - DstPort 1 - } + ZOrder 42 + SrcBlock "Demux2" + SrcPort 3 + DstBlock "Controller" + DstPort 7 } Line { - ZOrder 209 - SrcBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [58, 0] - Branch { - ZOrder 221 - Points [0, 160] - DstBlock "euler_rates" - DstPort 1 - } - Branch { - ZOrder 220 - Points [0, -80] - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 3 - } + ZOrder 68 + SrcBlock "Controller" + SrcPort 2 + DstBlock "Sum1" + DstPort 1 + } + Line { + ZOrder 72 + SrcBlock "Controller" + SrcPort 4 + DstBlock "Sum3" + DstPort 1 } Line { - ZOrder 208 - SrcBlock "Delay" + ZOrder 77 + SrcBlock "y_controlled_o" SrcPort 1 - Points [-102, 0] - Branch { - ZOrder 191 - Points [0, -115] - DstBlock "\n\n\n\n\n\n\n\n" - DstPort 4 - } - Branch { - ZOrder 190 - Points [-566, 0; 0, -80] - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 2 - } + Points [25, 0] + DstBlock "Sum1" + DstPort 2 } Line { - ZOrder 204 - SrcBlock "Delay1" + ZOrder 78 + SrcBlock "x_controlled_o" SrcPort 1 - Points [-199, 0; 0, -60] - DstBlock "\n\n\n\n\n\n\n\n\n\n\n\n1" + Points [25, 0] + DstBlock "Sum2" DstPort 2 } Line { - ZOrder 211 - SrcBlock "euler_angles" + ZOrder 79 + SrcBlock "yaw_controlled_o" SrcPort 1 - Points [23, 0] - Branch { - ZOrder 332 - Points [0, 70] - DstBlock "3D Graphical Simulation" - DstPort 2 - } - Branch { - ZOrder 293 - DstBlock "Demux" - DstPort 1 - } + Points [25, 0] + DstBlock "Sum3" + DstPort 2 } Line { - ZOrder 189 - SrcBlock "\n\n\n\n\n\n\n\n" + ZOrder 80 + SrcBlock "Signal Mixer" SrcPort 1 - Points [16, 0] - Branch { - ZOrder 327 - DstBlock "Demux1" - DstPort 1 - } - Branch { - ZOrder 216 - Points [0, 225] - DstBlock "Delay" - DstPort 1 - } - Branch { - ZOrder 187 - Points [0, -85] - DstBlock "Scope3" - DstPort 1 - } + DstBlock "Saturation" + DstPort 1 } Line { - ZOrder 243 - SrcBlock "First-Order\nHold" + ZOrder 84 + SrcBlock "Demux1" SrcPort 1 - Points [50, 0] - DstBlock "3D Graphical Simulation1" - DstPort 1 + DstBlock "Controller" + DstPort 8 } Line { - ZOrder 212 - SrcBlock "E_ro" + ZOrder 86 + SrcBlock "Demux1" + SrcPort 2 + DstBlock "Controller" + DstPort 9 + } + Line { + ZOrder 90 + SrcBlock "Demux4" SrcPort 1 - Points [196, 0] - Branch { - ZOrder 331 - Points [0, 120] - DstBlock "3D Graphical Simulation" - DstPort 1 - } - Branch { - ZOrder 304 - DstBlock "\n\n " - DstPort 1 - } + DstBlock "Controller" + DstPort 11 + } + Line { + ZOrder 91 + SrcBlock "Demux4" + SrcPort 2 + DstBlock "Controller" + DstPort 12 + } + Line { + ZOrder 93 + SrcBlock "Demux4" + SrcPort 3 + DstBlock "Controller" + DstPort 13 } Line { - ZOrder 305 + ZOrder 94 SrcBlock "Demux" + SrcPort 4 + DstBlock "Controller" + DstPort 4 + } + Line { + ZOrder 95 + SrcBlock "Demux1" SrcPort 3 - Points [23, 0; 0, -55] - DstBlock "\n\n " - DstPort 2 + DstBlock "Controller" + DstPort 10 } Line { - ZOrder 290 - SrcBlock "First-Order\nHold1" + ZOrder 131 + SrcBlock "Controller" + SrcPort 3 + DstBlock "Sum2" + DstPort 1 + } + Line { + ZOrder 205 + SrcBlock "Counter\nFree-Running" SrcPort 1 - Points [30, 0; 0, -30] - DstBlock "3D Graphical Simulation1" - DstPort 2 + DstBlock "MATLAB Function1" + DstPort 14 } Line { - ZOrder 333 - SrcBlock "Demux1" + ZOrder 235 + SrcBlock "Constant" SrcPort 1 - DstBlock "Mux" - DstPort 1 + Points [43, 0; 0, -45] + DstBlock "MATLAB Function1" + DstPort 15 } Line { - ZOrder 334 - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Mux" + ZOrder 501 + SrcBlock "Sum1" + SrcPort 1 + DstBlock "Signal Mixer" DstPort 2 } Line { - ZOrder 335 - SrcBlock "\n\n " - SrcPort 2 - Points [195, 0; 0, -345] - DstBlock "Mux" + ZOrder 500 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Signal Mixer" DstPort 3 } Line { - ZOrder 336 - SrcBlock "Mux" + ZOrder 499 + SrcBlock "Sum3" SrcPort 1 - Points [21, 0] - Branch { - ZOrder 339 - Points [0, 150] - DstBlock "First-Order\nHold" - DstPort 1 - } - Branch { - ZOrder 338 - DstBlock "euler_angles_filtered" - DstPort 1 - } + DstBlock "Signal Mixer" + DstPort 4 + } + Line { + ZOrder 495 + SrcBlock "Throttle Command Input" + SrcPort 1 + DstBlock "Signal Mixer" + DstPort 1 + } + Line { + ZOrder 519 + SrcBlock "Controller" + SrcPort 1 + DstBlock "Sum" + DstPort 1 + } + Line { + ZOrder 520 + SrcBlock "height_controlled_o" + SrcPort 1 + Points [25, 0] + DstBlock "Sum" + DstPort 2 } Line { - ZOrder 306 - SrcBlock "\n\n " + ZOrder 521 + SrcBlock "Motor Commands" SrcPort 1 - Points [70, 0] + Points [42, 0] Branch { - ZOrder 341 - Points [0, -80] - DstBlock "First-Order\nHold1" + ZOrder 540 + Points [0, 50] + DstBlock "Demux3" DstPort 1 } Branch { - ZOrder 340 - DstBlock "current_position" + ZOrder 539 + DstBlock "P" DstPort 1 } } - } - } - Block { - BlockType SubSystem - Name " \n" - SID "583" - Ports [4, 4] - Position [895, 478, 1075, 712] - ZOrder 65 - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 42 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Setpoints', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{filtered}', 'texmo" - "de', 'on');\nport_label('input', 3, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmo" - "de', 'on');\nport_label('output', 1, 'Rotor 1 Duty Cycle', 'texmode', 'on');\nport_label('output', 2, 'Rotor 2 Duty C" - "ycle', 'texmode', 'on');\nport_label('output', 3, 'Rotor 3 Duty Cycle', 'texmode', 'on');\nport_label('output', 4, 'R" - "otor 4 Duty Cycle', 'texmode', 'on');\ndisp('Control System', 'texmode', 'on');" - } - System { - Name " \n" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "125" - Block { - BlockType Inport - Name "setpoints" - SID "585" - Position [110, 348, 140, 362] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles_filtered" - SID "591" - Position [110, 403, 140, 417] - ZOrder 9 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_rates" - SID "592" - Position [110, 448, 140, 462] - ZOrder 11 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "current_position" - SID "584" - Position [110, 493, 140, 507] - ZOrder -1 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "Rotor 0 Duty Cycle" - SID "597" - Position [480, 348, 510, 362] - ZOrder -2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "Rotor 1 Duty Cycle" - SID "598" - Position [480, 403, 510, 417] - ZOrder 6 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "Rotor 2 Duty Cycle" - SID "599" - Position [480, 448, 510, 462] - ZOrder 7 - Port "3" - IconDisplay "Port number" + Line { + ZOrder 535 + SrcBlock "Demux3" + SrcPort 1 + DstBlock "Scope" + DstPort 1 } - Block { - BlockType Outport - Name "Rotor 3 Duty Cycle" - SID "600" - Position [480, 493, 510, 507] - ZOrder 8 - Port "4" - IconDisplay "Port number" + Line { + ZOrder 536 + SrcBlock "Demux3" + SrcPort 2 + DstBlock "Scope" + DstPort 2 } - } - } - Block { - BlockType SubSystem - Name "Communication System" - SID "574" - Ports [0, 1] - Position [760, 482, 815, 528] - ZOrder 66 - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 43 - $ClassName "Simulink.Mask" - Display "port_label('output', 1, 'Setpoints', 'texmode', 'on');" - } - System { - Name "Communication System" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "300" - Block { - BlockType Step - Name "Step" - SID "929" - Position [925, 390, 955, 420] - ZOrder 32 - Before "zeros(4,1)" - After "[0; 0; 0; 0]" - SampleTime "0" + Line { + ZOrder 537 + SrcBlock "Demux3" + SrcPort 3 + DstBlock "Scope" + DstPort 3 } - Block { - BlockType Outport - Name "setpoints" - SID "577" - Position [1050, 398, 1080, 412] - ZOrder 6 - IconDisplay "Port number" + Line { + ZOrder 538 + SrcBlock "Demux3" + SrcPort 4 + DstBlock "Scope" + DstPort 4 } Line { - ZOrder 8 - SrcBlock "Step" + ZOrder 543 + SrcBlock "Sum" SrcPort 1 - DstBlock "setpoints" + DstBlock "Throttle Command Input" DstPort 1 } + Line { + ZOrder 206 + SrcBlock "Saturation" + SrcPort 1 + Points [49, 0] + Branch { + ZOrder 557 + Points [0, -85] + DstBlock "To Workspace3" + DstPort 1 + } + Branch { + ZOrder 556 + DstBlock "Motor Commands" + DstPort 1 + } + } } } Line { - ZOrder 172 - SrcBlock " \n" + ZOrder 52 + SrcBlock "Control System" + SrcPort 1 + DstBlock "Actuation" + DstPort 1 + } + Line { + ZOrder 55 + SrcBlock "Communication System" + SrcPort 1 + DstBlock "Control System" + DstPort 1 + } + Line { + ZOrder 189 + SrcBlock "Actuation" SrcPort 1 - DstBlock "\n\n\n\n\n\n" + DstBlock " Sensors " DstPort 1 } Line { - ZOrder 260 - SrcBlock " " + ZOrder 190 + SrcBlock "Actuation" + SrcPort 2 + DstBlock " Sensors " + DstPort 2 + } + Line { + ZOrder 191 + SrcBlock "Actuation" + SrcPort 3 + DstBlock " Sensors " + DstPort 3 + } + Line { + ZOrder 192 + SrcBlock "Actuation" + SrcPort 4 + DstBlock " Sensors " + DstPort 4 + } + Line { + ZOrder 193 + SrcBlock "Actuation" + SrcPort 5 + DstBlock " Sensors " + DstPort 5 + } + Line { + ZOrder 194 + SrcBlock "Actuation" + SrcPort 6 + DstBlock " Sensors " + DstPort 6 + } + Line { + ZOrder 222 + SrcBlock " Sensors " + SrcPort 3 + Points [15, 0; 0, 56; -909, 0; 0, -56] + DstBlock "Control System" + DstPort 4 + } + Line { + ZOrder 223 + SrcBlock " Sensors " SrcPort 2 - Points [23, 0; 0, 147; -843, 0; 0, -117] - DstBlock " \n" + Points [33, 0; 0, 154; -941, 0; 0, -129] + DstBlock "Control System" DstPort 3 } - Line { - ZOrder 233 - SrcBlock " " - SrcPort 1 - Points [40, 0; 0, 246; -885, 0; 0, -196] - DstBlock " \n" - DstPort 2 + Line { + ZOrder 224 + SrcBlock " Sensors " + SrcPort 1 + Points [47, 0; 0, 247; -965, 0; 0, -197] + DstBlock "Control System" + DstPort 2 + } + } +} +#Finite State Machines +# +# Stateflow 80000010 +# +# +Stateflow { + machine { + id 1 + name "Quadcopter_Model_R2015_A" + created "03-Nov-2016 18:34:53" + isLibrary 0 + sfVersion 80000006 + firstTarget 197 + } + chart { + id 2 + machine 1 + name "Actuation/Gravity\n\n" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 3 0 0] + viewObj 2 + ssIdHighWaterMark 7 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 1 + disableImplicitCasting 1 + eml { + name "gravity" + } + firstData 4 + firstTransition 8 + firstJunction 7 + } + state { + id 3 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 2 + treeNode [2 0 0 0] + superState SUBCHART + subviewer 2 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function E_Fg = gravity(m, g)\n\nE_Fg = [0; 0; m*g];\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 4 + ssIdNumber 5 + name "E_Fg" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + linkNode [2 0 5] + } + data { + id 5 + ssIdNumber 6 + name "m" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [2 4 6] + } + data { + id 6 + ssIdNumber 7 + name "g" + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [2 5 0] + } + junction { + id 7 + position [23.5747 49.5747 7] + chart 2 + subviewer 2 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [2 0 0] + } + transition { + id 8 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 7 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 2 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 2 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [2 0 0] + } + instance { + id 9 + machine 1 + name "Actuation/Gravity\n\n" + chart 2 + } + chart { + id 10 + machine 1 + name "Actuation/Lbe\n\n\n\n\n\n" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 11 0 0] + viewObj 10 + ssIdHighWaterMark 11 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 2 + disableImplicitCasting 1 + eml { + name "linear_body_earth_conversion" + } + firstData 12 + firstTransition 16 + firstJunction 15 + } + state { + id 11 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 10 + treeNode [10 0 0 0] + superState SUBCHART + subviewer 10 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function E_ro = linear_body_earth_conversion(B_vo, euler_angles)\n\neuler_rates = zeros(3,1);\nE" + "_ro = zeros(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLeb = [cos(thet" + "a)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ..." + "\n cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(p" + "hi)*cos(psi); ...\n -sin(theta) , sin(phi)*cos(theta) , c" + "os(phi)*cos(theta) ];\n\nE_ro = Leb * B_vo;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 12 + ssIdNumber 7 + name "B_vo" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [10 0 13] + } + data { + id 13 + ssIdNumber 11 + name "euler_angles" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } - Line { - ZOrder 180 - SrcBlock "Communication System" - SrcPort 1 - DstBlock " \n" - DstPort 1 + dataType "Inherit: Same as Simulink" + linkNode [10 12 14] + } + data { + id 14 + ssIdNumber 9 + name "E_ro" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO } - Line { - ZOrder 186 - SrcBlock " \n" - SrcPort 2 - DstBlock "\n\n\n\n\n\n" - DstPort 2 + dataType "Inherit: Same as Simulink" + linkNode [10 13 0] + } + junction { + id 15 + position [23.5747 49.5747 7] + chart 10 + subviewer 10 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [10 0 0] + } + transition { + id 16 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] } - Line { - ZOrder 187 - SrcBlock " \n" - SrcPort 3 - DstBlock "\n\n\n\n\n\n" - DstPort 3 + dst { + id 15 + intersection [1 0 -1 0 23.5747 42.5747 0 0] } - Line { - ZOrder 188 - SrcBlock " \n" - SrcPort 4 - DstBlock "\n\n\n\n\n\n" - DstPort 4 + midPoint [23.5747 24.9468] + chart 10 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 10 + drawStyle SMART + slide { + sticky BOTH_STICK } - Line { - ZOrder 227 - SrcBlock "\n\n\n\n\n\n" - SrcPort 1 - DstBlock " " - DstPort 1 + executionOrder 1 + ssIdNumber 2 + linkNode [10 0 0] + } + instance { + id 17 + machine 1 + name "Actuation/Lbe\n\n\n\n\n\n" + chart 10 + } + chart { + id 18 + machine 1 + name " Sensors /3D Graphical Simulation1/MATLAB Function" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 19 0 0] + viewObj 18 + ssIdHighWaterMark 5 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 3 + disableImplicitCasting 1 + eml { + name "eigenaxis_ucart" } - Line { - ZOrder 229 - SrcBlock "\n\n\n\n\n\n" - SrcPort 2 - DstBlock " " - DstPort 2 + firstData 20 + firstTransition 23 + firstJunction 22 + } + state { + id 19 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 18 + treeNode [18 0 0 0] + superState SUBCHART + subviewer 18 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" + ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " + "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" + "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " + "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" + "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " + "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" + editorLayout "100 M4x1[10 5 700 500]" } - Line { - ZOrder 230 - SrcBlock "\n\n\n\n\n\n" - SrcPort 3 - DstBlock " " - DstPort 3 + } + data { + id 20 + ssIdNumber 4 + name "u" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED } - Line { - ZOrder 228 - SrcBlock "\n\n\n\n\n\n" - SrcPort 4 - DstBlock " " - DstPort 4 + dataType "Inherit: Same as Simulink" + linkNode [18 0 21] + } + data { + id 21 + ssIdNumber 5 + name "y" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO } - Line { - ZOrder 231 - SrcBlock "\n\n\n\n\n\n" - SrcPort 5 - DstBlock " " - DstPort 5 + dataType "Inherit: Same as Simulink" + linkNode [18 20 0] + } + junction { + id 22 + position [23.5747 49.5747 7] + chart 18 + subviewer 18 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [18 0 0] + } + transition { + id 23 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] } - Line { - ZOrder 232 - SrcBlock "\n\n\n\n\n\n" - SrcPort 6 - DstBlock " " - DstPort 6 + dst { + id 22 + intersection [1 0 -1 0 23.5747 42.5747 0 0] } - Line { - ZOrder 261 - SrcBlock " " - SrcPort 3 - Points [9, 0; 0, 51; -804, 0; 0, -41] - DstBlock " \n" - DstPort 4 + midPoint [23.5747 24.9468] + chart 18 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 18 + drawStyle SMART + slide { + sticky BOTH_STICK } + executionOrder 1 + ssIdNumber 2 + linkNode [18 0 0] } -} -#Finite State Machines -# -# Stateflow 80000010 -# -# -Stateflow { - machine { - id 1 - name "Quadcopter_Model_R2015_A" - created "27-Oct-2016 22:17:19" - isLibrary 0 - sfVersion 80000006 - firstTarget 139 + instance { + id 24 + machine 1 + name " Sensors /3D Graphical Simulation1/MATLAB Function" + chart 18 } chart { - id 2 + id 25 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n" + name "Actuation/ESC System" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 3 0 0] - viewObj 2 - ssIdHighWaterMark 7 + treeNode [0 26 0 0] + viewObj 25 + ssIdHighWaterMark 18 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 1 + chartFileNumber 4 disableImplicitCasting 1 eml { - name "gravity" + name "ESC" } - firstData 4 - firstTransition 8 - firstJunction 7 + firstData 27 + firstTransition 33 + firstJunction 32 } state { - id 3 + id 26 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 2 - treeNode [2 0 0 0] + chart 25 + treeNode [25 0 0 0] superState SUBCHART - subviewer 2 + subviewer 25 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function E_Fg = gravity( m, g)\n\nE_Fg = [0; 0; m*g];\n" + script "function Vb_eff = ESC(P, Pmin, Pmax, Vb)\n\nP1 = P(1);\nP2 = P(2);\nP3 = P(3);\nP4 = P(4);\n\n%" + " Define u_Pi for each of the rotors, limiting it to be greater than 0\n% u_P0 = (rotor_0_duty_cycle/100 - Pmin) " + "/ (Pmax - Pmin);\n% u_P1 = (rotor_1_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u_P2 = (rotor_2_duty_cycle/100 - " + "Pmin) / (Pmax - Pmin);\n% u_P3 = (rotor_3_duty_cycle/100 - Pmin) / (Pmax - Pmin);\nu_P0 = (P1 - Pmin) / (Pmax - " + "Pmin);\nu_P1 = (P2 - Pmin) / (Pmax - Pmin);\nu_P2 = (P3 - Pmin) / (Pmax - Pmin);\nu_P3 = (P4 - Pmin) / (Pmax - P" + "min);\n\n\n% Determine the effective battery voltage from each ESC\nVb_eff_0 = u_P0 * Vb;\nVb_eff_1 = u_P1 * Vb;" + "\nVb_eff_2 = u_P2 * Vb;\nVb_eff_3 = u_P3 * Vb;\n \nVb_eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];\n" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 4 + id 27 + ssIdNumber 4 + name "P" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [25 0 28] + } + data { + id 28 ssIdNumber 5 - name "E_Fg" + name "Vb_eff" scope OUTPUT_DATA machine 1 props { array { - size "-1" + size "1,4" } type { method SF_INHERITED_TYPE @@ -6716,12 +14497,12 @@ Stateflow { frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [2 0 5] + linkNode [25 27 29] } data { - id 5 - ssIdNumber 6 - name "m" + id 29 + ssIdNumber 16 + name "Pmin" scope PARAMETER_DATA paramIndexForInitFromWorkspace 1 machine 1 @@ -6739,12 +14520,12 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [2 4 6] + linkNode [25 28 30] } data { - id 6 - ssIdNumber 7 - name "g" + id 30 + ssIdNumber 17 + name "Pmax" scope PARAMETER_DATA machine 1 props { @@ -6761,19 +14542,42 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [2 5 0] + linkNode [25 29 31] + } + data { + id 31 + ssIdNumber 18 + name "Vb" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [25 30 0] } junction { - id 7 + id 32 position [23.5747 49.5747 7] - chart 2 - subviewer 2 + chart 25 + subviewer 25 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [2 0 0] + linkNode [25 0 0] } transition { - id 8 + id 33 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -6781,75 +14585,96 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 7 + id 32 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 2 + chart 25 dataLimits [21.175 25.975 14.625 42.575] - subviewer 2 + subviewer 25 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [2 0 0] + linkNode [25 0 0] } instance { - id 9 + id 34 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n" - chart 2 + name "Actuation/ESC System" + chart 25 } chart { - id 10 + id 35 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n" + name "Actuation/Motor System" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 11 0 0] - viewObj 10 - ssIdHighWaterMark 11 + treeNode [0 36 0 0] + viewObj 35 + ssIdHighWaterMark 16 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 2 + chartFileNumber 5 disableImplicitCasting 1 eml { - name "linear_body_earth_conversion" + name "motor" } - firstData 12 - firstTransition 16 - firstJunction 15 + firstData 37 + firstTransition 47 + firstJunction 46 } state { - id 11 + id 36 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 10 - treeNode [10 0 0 0] + chart 35 + treeNode [35 0 0 0] superState SUBCHART - subviewer 10 + subviewer 35 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function E_ro = linear_body_earth_conversion(B_vo, euler_angles)\n\neuler_rates = zeros(3,1);\nE" - "_ro = zeros(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLeb = [cos(thet" - "a)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ..." - "\n cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(p" - "hi)*cos(psi); ...\n -sin(theta) , sin(phi)*cos(theta) , c" - "os(phi)*cos(theta) ];\n\nE_ro = Leb * B_vo;" + script "function w_dot = motor(Vb_eff, w, Rm, Kv, Kq, Kd, If, Jreq)\n\n% Define each motors effective bat" + "tery voltage\nVb_eff_0 = Vb_eff(1);\nVb_eff_1 = Vb_eff(2);\nVb_eff_2 = Vb_eff(3);\nVb_eff_3 = Vb_eff(4);\n\n% De" + "termine the angular velocity of each rotor from feedback\nw_0 = w(1);\nw_1 = w(2);\nw_2 = w(3);\nw_3 = w(4);\n\n" + "% Determine angular acceleration of each rotor\nw_0_dot = 1/(Jreq*Rm*Kq) * Vb_eff_0 - 1/(Jreq*Rm*Kq*Kv) * w_0 - " + "1/(Jreq*Kq)*If - (Kd/Jreq) * w_0^2;\nw_1_dot = 1/(Jreq*Rm*Kq) * Vb_eff_1 - 1/(Jreq*Rm*Kq*Kv) * w_1 - 1/(Jreq*Kq)" + "*If - (Kd/Jreq) * w_1^2;\nw_2_dot = 1/(Jreq*Rm*Kq) * Vb_eff_2 - 1/(Jreq*Rm*Kq*Kv) * w_2 - 1/(Jreq*Kq)*If - (Kd/J" + "req) * w_2^2;\nw_3_dot = 1/(Jreq*Rm*Kq) * Vb_eff_3 - 1/(Jreq*Rm*Kq*Kv) * w_3 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_3^" + "2;\n\nw_dot = [w_0_dot, w_1_dot, w_2_dot, w_3_dot]; " editorLayout "100 M4x1[10 5 700 500]" } } data { - id 12 - ssIdNumber 7 - name "B_vo" + id 37 + ssIdNumber 4 + name "Vb_eff" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [35 0 38] + } + data { + id 38 + ssIdNumber 16 + name "w" scope INPUT_DATA machine 1 props { @@ -6866,13 +14691,127 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [10 0 13] + linkNode [35 37 39] } data { - id 13 + id 39 + ssIdNumber 7 + name "w_dot" + scope OUTPUT_DATA + machine 1 + props { + array { + size "1,4" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + linkNode [35 38 40] + } + data { + id 40 + ssIdNumber 9 + name "Rm" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 5 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [35 39 41] + } + data { + id 41 + ssIdNumber 10 + name "Kv" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 4 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [35 40 42] + } + data { + id 42 ssIdNumber 11 - name "euler_angles" - scope INPUT_DATA + name "Kq" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 3 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [35 41 43] + } + data { + id 43 + ssIdNumber 12 + name "Kd" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [35 42 44] + } + data { + id 44 + ssIdNumber 13 + name "If" + scope PARAMETER_DATA machine 1 props { array { @@ -6888,13 +14827,14 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [10 12 14] + linkNode [35 43 45] } data { - id 14 - ssIdNumber 9 - name "E_ro" - scope OUTPUT_DATA + id 45 + ssIdNumber 14 + name "Jreq" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 machine 1 props { array { @@ -6907,22 +14847,22 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [10 13 0] + linkNode [35 44 0] } junction { - id 15 + id 46 position [23.5747 49.5747 7] - chart 10 - subviewer 10 + chart 35 + subviewer 35 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [10 0 0] + linkNode [35 0 0] } transition { - id 16 + id 47 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -6930,77 +14870,99 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 15 + id 46 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 10 + chart 35 dataLimits [21.175 25.975 14.625 42.575] - subviewer 10 + subviewer 35 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [10 0 0] + linkNode [35 0 0] } instance { - id 17 + id 48 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n" - chart 10 + name "Actuation/Motor System" + chart 35 } chart { - id 18 + id 49 machine 1 - name " /3D Graphical Simulation1/MATLAB Function" + name "Actuation/Rotor System\n\n\n\n\n\n\n\n" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 19 0 0] - viewObj 18 - ssIdHighWaterMark 5 + treeNode [0 50 0 0] + viewObj 49 + ssIdHighWaterMark 31 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 3 + chartFileNumber 6 disableImplicitCasting 1 eml { - name "eigenaxis_ucart" + name "rotor" } - firstData 20 - firstTransition 23 - firstJunction 22 + firstData 51 + firstTransition 69 + firstJunction 68 } state { - id 19 + id 50 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 18 - treeNode [18 0 0 0] + chart 49 + treeNode [49 0 0 0] superState SUBCHART - subviewer 18 + subviewer 49 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" - ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " - "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" - "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " - "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" - "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " - "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" + script "function [B_omega_dot, B_vo_dot]= rotor(w_dot, w, B_Fg, B_omega, B_vo, m, Kt, Kd, rhx, rhy, rhz, " + "Jreq, Jxx, Jyy, Jzz)\n\n% Create J vector\nJ = [Jxx, 0 , 0 ; ...\n 0 , Jyy, 0 ; ...\n 0 , 0 , Jzz;" + "];\n\n% Create r_hi vector\nrh_0 = [-rhx; rhy; -rhz];\nrh_1 = [rhx; rhy; -rhz];\nrh_2 = [-rhx; -rhy; -rhz];\nrh_" + "3 = [rhx; -rhy; -rhz];\n\n% Define vector from body frame origin to center of mass\nbr_oc = [0; 0; 0];\n\n% Defi" + "ne 3x3 Identity Matrix\nI = eye(3);\n\n% Create gamma vectors\ngamma_Ti = [0; 0; -1];\ngamma_omega_03 = [0; 0; 1" + "]; %Rotors 0 and 3 use this gamma_omega vector\ngamma_omega_12 = [0; 0; -1]; %Rotors 1 and 2 use this gamma_ome" + "ga vector\n\n% Define angular velocities for each rotor\nw_0 = w(1);\nw_1 = w(2);\nw_2 = w(3);\nw_3 = w(4);\n\n%" + " Define angular acceleration for each rotor\nw_0_dot = w_dot(1);\nw_1_dot = w_dot(2);\nw_2_dot = w_dot(3);\nw_3_" + "dot = w_dot(4);\n\n% Define the rotor force in the z-direction from each rotor\nB_Fr_0 = Kt * w_0 * w_0 * gamma_" + "Ti;\nB_Fr_1 = Kt * w_1 * w_1 * gamma_Ti;\nB_Fr_2 = Kt * w_2 * w_2 * gamma_Ti;\nB_Fr_3 = Kt * w_3 * w_3 * gamma_T" + "i;\n\n% Sum up the rotor forces in the z-direction from each vector to get the\n% total body force in the z-dire" + "ction\nB_Fr = B_Fr_0 + B_Fr_1 + B_Fr_2 + B_Fr_3;\n\n% Define the in-plane drag and induced torque produced by ea" + "ch rotor\n B_Q_d0 = -1 * Kd * w_0 * w_0 * gamma_omega_03;\n B_Q_d1 = -1 * Kd * w_1 * w_1 * gamma_omega_12;\n B_Q" + "_d2 = -1 * Kd * w_2 * w_2 * gamma_omega_12;\n B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;\n\n% Sum up the tot" + "al in-plane drag and induced torque to get the total\n% in-plane drag and induced torque on the body\nB_Q_d = B_" + "Q_d0 + B_Q_d1 + B_Q_d2 + B_Q_d3;\n\n% Define the force lever arm torque created from the force produced by each\n" + "% rotor in the z-direction\nB_Q_F0 = cross( rh_0, B_Fr_0 );\nB_Q_F1 = cross( rh_1, B_Fr_1 );\nB_Q_F2 = cross( rh" + "_2, B_Fr_2 );\nB_Q_F3 = cross( rh_3, B_Fr_3 );\n\nB_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;\n\n%Define the chan" + "ge in angular momentum torque produced by each rotor \nB_Q_L0 = -1 * Jreq * ( cross(B_omega, w_0 * gamma_omega_0" + "3) + w_0_dot * gamma_omega_03 );\nB_Q_L1 = -1 * Jreq * ( cross(B_omega, w_1 * gamma_omega_12) + w_1_dot * gamma_" + "omega_12 ); \nB_Q_L2 = -1 * Jreq * ( cross(B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_omega_12 ); \nB_Q_L3" + " = -1 * Jreq * ( cross(B_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );\n\n% Sum up the total change" + " in angular momentum torque produced by each rotor\nB_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;\n\n% Define the t" + "otal rotor system torque as the sum of the in-plane drag and\n% induced torque, force lever arm torque, and chan" + "ge in angular momentum\n% torques\nB_Q = B_Q_d + B_Q_F + B_Q_L;\n\n% Define the body forces in the z-direction f" + "rom each vector to get the\n% total body force in the z-direction\nB_F = B_Fr + B_Fg; \n\n% Define the body fram" + "e linear velocities\nB_vo_dot = (m*I)^(-1) * ( B_F - cross( B_omega, m*(B_vo + cross(B_omega, br_oc)) ) );\n\n% " + "Define the body frame angular velocities\nB_omega_dot = J ^(-1) * ( B_Q - cross(B_omega, J * B_omega) - cross(br" + "_oc, B_F) );\n\n" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 20 - ssIdNumber 4 - name "u" - scope INPUT_DATA + id 51 + ssIdNumber 6 + name "B_omega_dot" + scope OUTPUT_DATA machine 1 props { array { @@ -7009,17 +14971,20 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [18 0 21] + linkNode [49 0 52] } data { - id 21 - ssIdNumber 5 - name "y" - scope OUTPUT_DATA + id 52 + ssIdNumber 10 + name "w_dot" + scope INPUT_DATA machine 1 props { array { @@ -7028,101 +14993,175 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [18 20 0] + linkNode [49 51 53] } - junction { - id 22 - position [23.5747 49.5747 7] - chart 18 - subviewer 18 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [18 0 0] + data { + id 53 + ssIdNumber 11 + name "w" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [49 52 54] } - transition { - id 23 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] + data { + id 54 + ssIdNumber 30 + name "B_Fg" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } - dst { - id 22 - intersection [1 0 -1 0 23.5747 42.5747 0 0] + dataType "Inherit: Same as Simulink" + linkNode [49 53 55] + } + data { + id 55 + ssIdNumber 8 + name "B_omega" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } - midPoint [23.5747 24.9468] - chart 18 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 18 - drawStyle SMART - slide { - sticky BOTH_STICK + dataType "Inherit: Same as Simulink" + linkNode [49 54 56] + } + data { + id 56 + ssIdNumber 5 + name "B_vo_dot" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO } - executionOrder 1 - ssIdNumber 2 - linkNode [18 0 0] + dataType "Inherit: Same as Simulink" + linkNode [49 55 57] } - instance { - id 24 + data { + id 57 + ssIdNumber 7 + name "B_vo" + scope INPUT_DATA machine 1 - name " /3D Graphical Simulation1/MATLAB Function" - chart 18 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [49 56 58] } - chart { - id 25 + data { + id 58 + ssIdNumber 12 + name "m" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 6 machine 1 - name "\n\n\n\n\n\n/\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 26 0 0] - viewObj 25 - ssIdHighWaterMark 18 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 4 - disableImplicitCasting 1 - eml { - name "ESC" + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } - firstData 27 - firstTransition 36 - firstJunction 35 + dataType "Inherit: Same as Simulink" + linkNode [49 57 59] } - state { - id 26 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 25 - treeNode [25 0 0 0] - superState SUBCHART - subviewer 25 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function Vb_eff = ESC(rotor_0_duty_cycle, rotor_1_duty_cycle, rotor_2_duty_cycle, rotor_3_duty_" - "cycle, Pmin, Pmax, Vb)\n\n% Define u_Pi for each of the rotors\nu_P0 = (rotor_0_duty_cycle/100 - Pmin) / (Pmax -" - " Pmin);\nu_P1 = (rotor_1_duty_cycle/100 - Pmin) / (Pmax - Pmin);\nu_P2 = (rotor_2_duty_cycle/100 - Pmin) / (Pmax" - " - Pmin);\nu_P3 = (rotor_3_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n\n% Determine the effective battery voltage " - "from each ESC\nVb_eff_0 = u_P0 * Vb;\nVb_eff_1 = u_P1 * Vb;\nVb_eff_2 = u_P2 * Vb;\nVb_eff_3 = u_P3 * Vb;\n\nVb_" - "eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];\n" - editorLayout "100 M4x1[10 5 700 500]" + data { + id 59 + ssIdNumber 14 + name "Kt" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 5 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } + dataType "Inherit: Same as Simulink" + linkNode [49 58 60] } data { - id 27 - ssIdNumber 4 - name "rotor_0_duty_cycle" - scope INPUT_DATA + id 60 + ssIdNumber 13 + name "Kd" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 4 machine 1 props { array { @@ -7131,17 +15170,21 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 0 28] + linkNode [49 59 61] } data { - id 28 - ssIdNumber 5 - name "Vb_eff" - scope OUTPUT_DATA + id 61 + ssIdNumber 15 + name "rhx" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 7 machine 1 props { array { @@ -7150,18 +15193,21 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 27 29] + linkNode [49 60 62] } data { - id 29 - ssIdNumber 6 - name "rotor_1_duty_cycle" - scope INPUT_DATA + id 62 + ssIdNumber 16 + name "rhy" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 8 machine 1 props { array { @@ -7177,13 +15223,14 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 28 30] + linkNode [49 61 63] } data { - id 30 - ssIdNumber 7 - name "rotor_2_duty_cycle" - scope INPUT_DATA + id 63 + ssIdNumber 17 + name "rhz" + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 9 machine 1 props { array { @@ -7199,13 +15246,13 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 29 31] + linkNode [49 62 64] } data { - id 31 - ssIdNumber 8 - name "rotor_3_duty_cycle" - scope INPUT_DATA + id 64 + ssIdNumber 18 + name "Jreq" + scope PARAMETER_DATA machine 1 props { array { @@ -7221,12 +15268,12 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 30 32] + linkNode [49 63 65] } data { - id 32 - ssIdNumber 16 - name "Pmin" + id 65 + ssIdNumber 19 + name "Jxx" scope PARAMETER_DATA paramIndexForInitFromWorkspace 1 machine 1 @@ -7244,13 +15291,14 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 31 33] + linkNode [49 64 66] } data { - id 33 - ssIdNumber 17 - name "Pmax" + id 66 + ssIdNumber 20 + name "Jyy" scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 machine 1 props { array { @@ -7266,14 +15314,14 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 32 34] + linkNode [49 65 67] } data { - id 34 - ssIdNumber 18 - name "Vb" + id 67 + ssIdNumber 21 + name "Jzz" scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 + paramIndexForInitFromWorkspace 3 machine 1 props { array { @@ -7289,19 +15337,19 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [25 33 0] + linkNode [49 66 0] } junction { - id 35 + id 68 position [23.5747 49.5747 7] - chart 25 - subviewer 25 + chart 49 + subviewer 49 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [25 0 0] + linkNode [49 0 0] } transition { - id 36 + id 69 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -7309,97 +15357,73 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 35 + id 68 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 25 + chart 49 dataLimits [21.175 25.975 14.625 42.575] - subviewer 25 + subviewer 49 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [25 0 0] + linkNode [49 0 0] } instance { - id 37 + id 70 machine 1 - name "\n\n\n\n\n\n/\n\n" - chart 25 + name "Actuation/Rotor System\n\n\n\n\n\n\n\n" + chart 49 } chart { - id 38 + id 71 machine 1 - name "\n\n\n\n\n\n/\n" + name "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 39 0 0] - viewObj 38 - ssIdHighWaterMark 14 + treeNode [0 72 0 0] + viewObj 71 + ssIdHighWaterMark 6 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 5 + chartFileNumber 7 disableImplicitCasting 1 eml { - name "motor" + name "angular_body_earth_conversion" } - firstData 40 - firstTransition 50 - firstJunction 49 + firstData 73 + firstTransition 77 + firstJunction 76 } state { - id 39 + id 72 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 38 - treeNode [38 0 0 0] + chart 71 + treeNode [71 0 0 0] superState SUBCHART - subviewer 38 + subviewer 71 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function angular_acceleration = motor(Vb_eff, angular_velocity, Rm, Kv, Kq, Kd, If, Jreq)\n\n% D" - "efine each motors effective battery voltage\nVb_eff_0 = Vb_eff(1);\nVb_eff_1 = Vb_eff(2);\nVb_eff_2 = Vb_eff(3);" - "\nVb_eff_3 = Vb_eff(4);\n\n% Determine the angular velocity of each rotor from feedback\nw_0 = angular_velocity(" - "1);\nw_1 = angular_velocity(2);\nw_2 = angular_velocity(3);\nw_3 = angular_velocity(4);\n\n% Determine angular a" - "cceleration of each rotor\nw_0_dot = 1/(Jreq*Rm*Kq) * Vb_eff_0 - 1/(Jreq*Rm*Kq*Kv) * w_0 - 1/(Jreq*Kq)*If - (Kd/" - "Jreq) * w_0^2;\nw_1_dot = 1/(Jreq*Rm*Kq) * Vb_eff_1 - 1/(Jreq*Rm*Kq*Kv) * w_1 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_1" - "^2;\nw_2_dot = 1/(Jreq*Rm*Kq) * Vb_eff_2 - 1/(Jreq*Rm*Kq*Kv) * w_2 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_2^2;\nw_3_do" - "t = 1/(Jreq*Rm*Kq) * Vb_eff_3 - 1/(Jreq*Rm*Kq*Kv) * w_3 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_3^2;\n\nangular_acceler" - "ation = [w_0_dot, w_1_dot, w_2_dot, w_3_dot]; " + script "function euler_rates = angular_body_earth_conversion(B_omega, euler_angles)\n\nphi = euler_angles" + "(1);\ntheta = euler_angles(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta); ...\n 0, cos(p" + "hi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)/cos(theta)];\n\n \neuler_rates " + "= Aeb * B_omega;\n " editorLayout "100 M4x1[10 5 700 500]" } } data { - id 40 + id 73 ssIdNumber 4 - name "Vb_eff" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [38 0 41] - } - data { - id 41 - ssIdNumber 8 - name "angular_velocity" + name "B_omega" scope INPUT_DATA machine 1 props { @@ -7409,43 +15433,37 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [38 40 42] + linkNode [71 0 74] } data { - id 42 - ssIdNumber 7 - name "angular_acceleration" + id 74 + ssIdNumber 5 + name "euler_rates" scope OUTPUT_DATA machine 1 props { array { - size "1,4" + size "-1" } type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [38 41 43] + linkNode [71 73 75] } data { - id 43 - ssIdNumber 9 - name "Rm" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 5 + id 75 + ssIdNumber 6 + name "euler_angles" + scope INPUT_DATA machine 1 props { array { @@ -7461,14 +15479,96 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [38 42 44] + linkNode [71 74 0] + } + junction { + id 76 + position [23.5747 49.5747 7] + chart 71 + subviewer 71 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [71 0 0] + } + transition { + id 77 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 76 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 71 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 71 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [71 0 0] + } + instance { + id 78 + machine 1 + name "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + chart 71 + } + chart { + id 79 + machine 1 + name "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 80 0 0] + viewObj 79 + ssIdHighWaterMark 13 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 8 + disableImplicitCasting 1 + eml { + name "linear_earth_body_conversion" + } + firstData 81 + firstTransition 87 + firstJunction 86 + } + state { + id 80 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 79 + treeNode [79 0 0 0] + superState SUBCHART + subviewer 79 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [B_Fg, B_g] = linear_earth_body_conversion(E_Fg, euler_angles, m)\n\nphi = euler_angles" + "(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLbe = [ cos(theta)*cos(psi) ," + " cos(theta)*sin(psi) , -sin(theta) ; ...\n sin(phi)*sin(theta)*cos(psi)-c" + "os(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...\n cos(phi)*sin(" + "theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];\n\nB_Fg" + " = Lbe * E_Fg;\n\nB_g = B_Fg/m;" + editorLayout "100 M4x1[10 5 700 500]" + } } data { - id 44 - ssIdNumber 10 - name "Kv" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 4 + id 81 + ssIdNumber 7 + name "E_Fg" + scope INPUT_DATA machine 1 props { array { @@ -7484,18 +15584,17 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [38 43 45] + linkNode [79 0 82] } data { - id 45 + id 82 ssIdNumber 11 - name "Kq" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 3 + name "euler_angles" + scope INPUT_DATA machine 1 props { array { - size "-1" + size "3" } type { method SF_INHERITED_TYPE @@ -7507,18 +15606,17 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [38 44 46] + linkNode [79 81 83] } data { - id 46 - ssIdNumber 12 - name "Kd" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 + id 83 + ssIdNumber 9 + name "B_Fg" + scope OUTPUT_DATA machine 1 props { array { - size "-1" + size "3" } type { method SF_INHERITED_TYPE @@ -7527,16 +15625,16 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [38 45 47] + linkNode [79 82 84] } data { - id 47 - ssIdNumber 13 - name "If" - scope PARAMETER_DATA + id 84 + ssIdNumber 12 + name "B_g" + scope OUTPUT_DATA machine 1 props { array { @@ -7549,17 +15647,16 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [38 46 48] + linkNode [79 83 85] } data { - id 48 - ssIdNumber 14 - name "Jreq" + id 85 + ssIdNumber 13 + name "m" scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 machine 1 props { array { @@ -7575,19 +15672,19 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [38 47 0] + linkNode [79 84 0] } junction { - id 49 + id 86 position [23.5747 49.5747 7] - chart 38 - subviewer 38 + chart 79 + subviewer 79 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [38 0 0] + linkNode [79 0 0] } transition { - id 50 + id 87 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -7595,100 +15692,73 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 49 + id 86 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 38 + chart 79 dataLimits [21.175 25.975 14.625 42.575] - subviewer 38 + subviewer 79 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [38 0 0] + linkNode [79 0 0] } instance { - id 51 + id 88 machine 1 - name "\n\n\n\n\n\n/\n" - chart 38 + name "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + chart 79 } chart { - id 52 + id 89 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n\n" + name " Sensors /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 53 0 0] - viewObj 52 - ssIdHighWaterMark 30 + treeNode [0 90 0 0] + viewObj 89 + ssIdHighWaterMark 15 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 6 + chartFileNumber 10 disableImplicitCasting 1 eml { - name "rotor" + name "idealIMU" } - firstData 54 - firstTransition 72 - firstJunction 71 + firstData 91 + firstTransition 100 + firstJunction 99 } state { - id 53 + id 90 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 52 - treeNode [52 0 0 0] + chart 89 + treeNode [89 0 0 0] superState SUBCHART - subviewer 52 + subviewer 89 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function [B_omega_dot, B_vo_dot]= rotor(angular_acceleration, angular_velocity, B_Fg, B_omega, B_" - "vo, m, Kt, Kd, rhx, rhy, rhz, Jreq, Jxx, Jyy, Jzz)\n\nB_vo_dot = zeros(3,1);\nB_omega_dot = zeros(3,1);\n\n% Cre" - "ate J vector\nJ = [Jxx, 0 , 0 ; ...\n 0 , Jyy, 0 ; ...\n 0 , 0 , Jzz;];\n\n% Create r_hi vector\nr" - "h_0 = [-rhx; rhy; rhz];\nrh_1 = [rhx; rhy; rhz];\nrh_2 = [-rhx; -rhy; rhz];\nrh_3 = [rhx; -rhy; rhz];\n\n% Defin" - "e vector from body frame origin to center of mass\nbr_oc = [0; 0; 0];\n\n% Define 3x3 Identity Matrix\nI = eye(3" - ");\n\n% Create gamma vectors\ngamma_Ti = [0; 0; -1];\ngamma_omega_03 = [0; 0; -1]; %Rotors 0 and 3 use this gam" - "ma_omega vector\ngamma_omega_12 = [0; 0; 1]; %Rotors 1 and 2 use this gamma_omega vector\n\n% Define angular vel" - "ocities for each rotor\nw_0 = angular_velocity(1);\nw_1 = angular_velocity(2);\nw_2 = angular_velocity(3);\nw_3 " - "= angular_velocity(4);\n\n% Define angular acceleration for each rotor\nw_0_dot = angular_acceleration(1);\nw_1_" - "dot = angular_acceleration(2);\nw_2_dot = angular_acceleration(3);\nw_3_dot = angular_acceleration(4);\n\n% Defi" - "ne the rotor force in the z-direction from each rotor\nB_Fr_0 = Kt * w_0 * w_0 * gamma_Ti;\nB_Fr_1 = Kt * w_1 * " - "w_1 * gamma_Ti;\nB_Fr_2 = Kt * w_2 * w_2 * gamma_Ti;\nB_Fr_3 = Kt * w_3 * w_3 * gamma_Ti;\n\n% Sum up the rotor " - "forces in the z-direction from each vector to get the\n% total body force in the z-direction\nB_Fr = B_Fr_0 + B_" - "Fr_1 + B_Fr_2 + B_Fr_3;\n\n% Define the in-plane drag and induced torque produced by each rotor\n B_Q_d0 = -1 * " - "Kd * w_0 * w_0 * gamma_omega_03;\n B_Q_d1 = -1 * Kd * w_1 * w_1 * gamma_omega_12;\n B_Q_d2 = -1 * Kd * w_2 * w_2" - " * gamma_omega_12;\n B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;\n\n% Sum up the total in-plane drag and indu" - "ced torque to get the total\n% in-plane drag and induced torque on the body\nB_Q_d = B_Q_d0 + B_Q_d1 + B_Q_d2 + " - "B_Q_d3;\n\n% Define the force lever arm torque created from the force produced by each\n% rotor in the z-directi" - "on\nB_Q_F0 = cross( rh_0, B_Fr_0 );\nB_Q_F1 = cross( rh_1, B_Fr_1 );\nB_Q_F2 = cross( rh_2, B_Fr_2 );\nB_Q_F3 = " - "cross( rh_3, B_Fr_3 );\n\nB_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;\n\n%Define the change in angular momentum t" - "orque produced by each rotor \nB_Q_L0 = -1 * Jreq * ( cross(B_omega, w_0 * gamma_omega_03) + w_0_dot * gamma_ome" - "ga_03 );\nB_Q_L1 = -1 * Jreq * ( cross(B_omega, w_1 * gamma_omega_12) + w_1_dot * gamma_omega_12 ); \nB_Q_L2 = -" - "1 * Jreq * ( cross(B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_omega_12 ); \nB_Q_L3 = -1 * Jreq * ( cross(B" - "_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );\n\n% Sum up the total change in angular momentum tor" - "que produced by each rotor\nB_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;\n\n% Define the total rotor system torque" - " as the sum of the in-plane drag and\n% induced torque, force lever arm torque, and change in angular momentum\n" - "% torques\nB_Q = B_Q_d + B_Q_F + B_Q_L;\n\n% Define the body forces in the z-direction from each vector to get t" - "he\n% total body force in the z-direction\nB_F = B_Fr + B_Fg; \n\n% Define the body frame linear velocities\nB_v" - "o_dot = (m*I)^(-1) * ( B_F - cross( B_omega, m*(B_vo + cross(B_omega, br_oc)) ) );\n\n% Define the body frame an" - "gular velocities\nB_omega_dot = J ^(-1) * ( B_Q - cross(B_omega, J * B_omega) - cross(br_oc, B_F) );\n\n" + script "function [accelReading,gyroReading] = idealIMU(B_vo_dot, B_vo, B_Omega, B_g, r_oc, g)\n%#codegen\n" + "\na = B_vo_dot + cross(B_Omega,B_vo); % body frame acceleration \n\naccelReading = (a - B_g)/g ; % accelerometer" + " reading (ideal)\n\ngyroReading = B_Omega ; % gyroscope reading (ideal) \n\nend\n\n" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 54 - ssIdNumber 6 - name "B_omega_dot" - scope OUTPUT_DATA + id 91 + ssIdNumber 4 + name "B_vo_dot" + scope INPUT_DATA machine 1 props { array { @@ -7697,19 +15767,16 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [52 0 55] + linkNode [89 0 92] } data { - id 55 - ssIdNumber 10 - name "angular_acceleration" + id 92 + ssIdNumber 9 + name "B_vo" scope INPUT_DATA machine 1 props { @@ -7726,13 +15793,13 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 54 56] + linkNode [89 91 93] } data { - id 56 - ssIdNumber 11 - name "angular_velocity" - scope INPUT_DATA + id 93 + ssIdNumber 5 + name "accelReading" + scope OUTPUT_DATA machine 1 props { array { @@ -7741,19 +15808,17 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [52 55 57] + linkNode [89 92 94] } data { - id 57 - ssIdNumber 30 - name "B_Fg" + id 94 + ssIdNumber 6 + name "B_Omega" scope INPUT_DATA machine 1 props { @@ -7770,12 +15835,12 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 56 58] + linkNode [89 93 95] } data { - id 58 - ssIdNumber 8 - name "B_omega" + id 95 + ssIdNumber 7 + name "B_g" scope INPUT_DATA machine 1 props { @@ -7792,12 +15857,12 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 57 59] + linkNode [89 94 96] } data { - id 59 - ssIdNumber 5 - name "B_vo_dot" + id 96 + ssIdNumber 8 + name "gyroReading" scope OUTPUT_DATA machine 1 props { @@ -7807,17 +15872,19 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [52 58 60] + linkNode [89 95 97] } data { - id 60 - ssIdNumber 7 - name "B_vo" + id 97 + ssIdNumber 10 + name "r_oc" scope INPUT_DATA machine 1 props { @@ -7834,14 +15901,13 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 59 61] + linkNode [89 96 98] } data { - id 61 + id 98 ssIdNumber 12 - name "m" + name "g" scope PARAMETER_DATA - paramIndexForInitFromWorkspace 6 machine 1 props { array { @@ -7857,14 +15923,116 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 60 62] + linkNode [89 97 0] + } + junction { + id 99 + position [23.5747 49.5747 7] + chart 89 + subviewer 89 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [89 0 0] + } + transition { + id 100 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 99 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 89 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 89 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [89 0 0] + } + instance { + id 101 + machine 1 + name " Sensors /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n" + chart 89 + } + chart { + id 102 + machine 1 + name " Sensors /3D Graphical Simulation/MATLAB Function" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 103 0 0] + viewObj 102 + ssIdHighWaterMark 5 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 11 + disableImplicitCasting 1 + eml { + name "eigenaxis_ucart" + } + firstData 104 + firstTransition 107 + firstJunction 106 + } + state { + id 103 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 102 + treeNode [102 0 0 0] + superState SUBCHART + subviewer 102 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" + ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " + "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" + "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " + "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" + "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " + "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 104 + ssIdNumber 4 + name "u" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [102 0 105] } data { - id 62 - ssIdNumber 14 - name "Kt" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 5 + id 105 + ssIdNumber 5 + name "y" + scope OUTPUT_DATA machine 1 props { array { @@ -7873,21 +16041,99 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [52 61 63] + linkNode [102 104 0] + } + junction { + id 106 + position [23.5747 49.5747 7] + chart 102 + subviewer 102 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [102 0 0] + } + transition { + id 107 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 106 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 102 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 102 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [102 0 0] + } + instance { + id 108 + machine 1 + name " Sensors /3D Graphical Simulation/MATLAB Function" + chart 102 + } + chart { + id 109 + machine 1 + name " Sensors /Aeb\n\n\n\n\n\n\n\n\n\n" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 110 0 0] + viewObj 109 + ssIdHighWaterMark 6 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 12 + disableImplicitCasting 1 + eml { + name "angular_body_earth_conversion" + } + firstData 111 + firstTransition 115 + firstJunction 114 + } + state { + id 110 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 109 + treeNode [109 0 0 0] + superState SUBCHART + subviewer 109 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_filtered)\n\n" + "phi = euler_angles_filtered(1);\ntheta = euler_angles_filtered(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*ta" + "n(theta); ...\n 0, cos(phi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)" + "/cos(theta)];\n\n \neuler_rates_IMU = Aeb * gyro_reading;\n " + editorLayout "100 M4x1[10 5 700 500]" + } } data { - id 63 - ssIdNumber 13 - name "Kd" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 4 + id 111 + ssIdNumber 4 + name "gyro_reading" + scope INPUT_DATA machine 1 props { array { @@ -7896,44 +16142,37 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 62 64] + linkNode [109 0 112] } data { - id 64 - ssIdNumber 15 - name "rhx" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 7 + id 112 + ssIdNumber 5 + name "euler_rates_IMU" + scope OUTPUT_DATA machine 1 props { array { - size "-1" + size "[3,1]" } type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [52 63 65] + linkNode [109 111 113] } data { - id 65 - ssIdNumber 16 - name "rhy" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 8 + id 113 + ssIdNumber 6 + name "euler_angles_filtered" + scope INPUT_DATA machine 1 props { array { @@ -7949,36 +16188,97 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 64 66] + linkNode [109 112 0] } - data { - id 66 - ssIdNumber 17 - name "rhz" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 9 + junction { + id 114 + position [23.5747 49.5747 7] + chart 109 + subviewer 109 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [109 0 0] + } + transition { + id 115 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 114 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 109 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 109 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [109 0 0] + } + instance { + id 116 machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + name " Sensors /Aeb\n\n\n\n\n\n\n\n\n\n" + chart 109 + } + chart { + id 117 + machine 1 + name " Sensors /Calculate Pitch and Roll" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 118 0 0] + viewObj 117 + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 13 + disableImplicitCasting 1 + eml { + name "getPitchAndRoll" + } + firstData 119 + firstTransition 124 + firstJunction 123 + } + state { + id 118 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 117 + treeNode [117 0 0 0] + superState SUBCHART + subviewer 117 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [accel_pitch, accel_roll] = getPitchAndRoll(accel_reading, accel_roll_prev)\n\nmag = nor" + "m(accel_reading);\n\n% x_accel = accel_reading(1)/mag;\n% y_accel = accel_reading(2)/mag;\n% z_accel = accel_rea" + "ding(3)/mag;\n\nx_accel = accel_reading(1);\ny_accel = accel_reading(2);\nz_accel = accel_reading(3);\n\naccel_p" + "itch = atan(x_accel/sqrt(y_accel^2 + z_accel^2));\n\n%accel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^" + "2 + (1/100)*x_accel^2)) );\n\n%accel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^2 + x_accel^2)) );\nacc" + "el_roll = atan( -y_accel/( sqrt(z_accel^2 + x_accel^2)) );\n\n% unwrapped_roll = unwrap([accel_roll_prev accel_" + "roll]);\n% accel_roll = unwrapped_roll(2);\n" + editorLayout "100 M4x1[10 5 700 500]" } - dataType "Inherit: Same as Simulink" - linkNode [52 65 67] } data { - id 67 - ssIdNumber 18 - name "Jreq" - scope PARAMETER_DATA + id 119 + ssIdNumber 4 + name "accel_reading" + scope INPUT_DATA machine 1 props { array { @@ -7987,21 +16287,17 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 66 68] + linkNode [117 0 120] } data { - id 68 - ssIdNumber 19 - name "Jxx" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 + id 120 + ssIdNumber 5 + name "accel_pitch" + scope OUTPUT_DATA machine 1 props { array { @@ -8010,21 +16306,18 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [52 67 69] + linkNode [117 119 121] } data { - id 69 - ssIdNumber 20 - name "Jyy" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 + id 121 + ssIdNumber 6 + name "accel_roll" + scope OUTPUT_DATA machine 1 props { array { @@ -8037,17 +16330,16 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [52 68 70] + linkNode [117 120 122] } data { - id 70 - ssIdNumber 21 - name "Jzz" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 3 + id 122 + ssIdNumber 7 + name "accel_roll_prev" + scope INPUT_DATA machine 1 props { array { @@ -8063,19 +16355,19 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [52 69 0] + linkNode [117 121 0] } junction { - id 71 + id 123 position [23.5747 49.5747 7] - chart 52 - subviewer 52 + chart 117 + subviewer 117 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [52 0 0] + linkNode [117 0 0] } transition { - id 72 + id 124 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -8083,73 +16375,74 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 71 + id 123 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 52 + chart 117 dataLimits [21.175 25.975 14.625 42.575] - subviewer 52 + subviewer 117 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [52 0 0] + linkNode [117 0 0] } instance { - id 73 + id 125 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n\n" - chart 52 + name " Sensors /Calculate Pitch and Roll" + chart 117 } chart { - id 74 + id 126 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + name "Control System/Signal Mixer" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 75 0 0] - viewObj 74 - ssIdHighWaterMark 6 + treeNode [0 127 0 0] + viewObj 126 + ssIdHighWaterMark 11 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 7 + chartFileNumber 14 disableImplicitCasting 1 eml { - name "angular_body_earth_conversion" + name "signal_mixer" } - firstData 76 - firstTransition 80 - firstJunction 79 + firstData 128 + firstTransition 134 + firstJunction 133 } state { - id 75 + id 127 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 74 - treeNode [74 0 0 0] + chart 126 + treeNode [126 0 0 0] superState SUBCHART - subviewer 74 + subviewer 126 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function euler_rates = angular_body_earth_conversion(B_omega, euler_angles)\n\neuler_rates = zero" - "s(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta" - "); ...\n 0, cos(phi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)/cos(th" - "eta)];\n\n \neuler_rates = Aeb * B_omega;\n " + script "function P = signal_mixer(height_controlled, y_controlled, x_controlled, yaw_controlled)\n\ncont" + "roller_outputs = [ height_controlled; x_controlled; y_controlled; yaw_controlled ];\nsignal_mixer = [ 1, -1, -1," + " -1; ... \n 1, 1, -1, 1; ...\n 1, -1, 1, 1; ...\n 1, 1, 1," + " -1 ];\n\n% signal_mixer = [ 1, 1, -1, -1; ... \n% 1, -1, -1, 1; ...\n% 1, " + "1, 1, 1; ...\n% 1, -1, 1, -1 ];\n \nP = signal_mixer * controller_outputs;\n" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 76 + id 128 ssIdNumber 4 - name "B_omega" + name "height_controlled" scope INPUT_DATA machine 1 props { @@ -8163,12 +16456,34 @@ Stateflow { complexity SF_COMPLEX_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [74 0 77] + linkNode [126 0 129] } data { - id 77 + id 129 + ssIdNumber 7 + name "y_controlled" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [126 128 130] + } + data { + id 130 ssIdNumber 5 - name "euler_rates" + name "P" scope OUTPUT_DATA machine 1 props { @@ -8183,12 +16498,34 @@ Stateflow { frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [74 76 78] + linkNode [126 129 131] } data { - id 78 + id 131 ssIdNumber 6 - name "euler_angles" + name "x_controlled" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [126 130 132] + } + data { + id 132 + ssIdNumber 8 + name "yaw_controlled" scope INPUT_DATA machine 1 props { @@ -8205,19 +16542,19 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [74 77 0] + linkNode [126 131 0] } junction { - id 79 + id 133 position [23.5747 49.5747 7] - chart 74 - subviewer 74 + chart 126 + subviewer 126 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [74 0 0] + linkNode [126 0 0] } transition { - id 80 + id 134 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -8225,75 +16562,116 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 79 + id 133 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 74 + chart 126 dataLimits [21.175 25.975 14.625 42.575] - subviewer 74 + subviewer 126 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [74 0 0] + linkNode [126 0 0] } instance { - id 81 + id 135 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - chart 74 + name "Control System/Signal Mixer" + chart 126 } chart { - id 82 + id 136 machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + name "Control System/MATLAB Function1" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 83 0 0] - viewObj 82 - ssIdHighWaterMark 13 + treeNode [0 137 0 0] + viewObj 136 + ssIdHighWaterMark 25 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 8 + chartFileNumber 15 disableImplicitCasting 1 eml { - name "linear_earth_body_conversion" + name "c_controller" } - firstData 84 - firstTransition 90 - firstJunction 89 + firstData 138 + firstTransition 160 + firstJunction 159 } state { - id 83 + id 137 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 82 - treeNode [82 0 0 0] + chart 136 + treeNode [136 0 0 0] superState SUBCHART - subviewer 82 + subviewer 136 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function [B_Fg, B_g] = linear_earth_body_conversion(E_Fg, euler_angles, m)\n\nphi = euler_angles" - "(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLbe = [ cos(theta)*cos(psi) ," - " cos(theta)*sin(psi) , -sin(theta) ; ...\n sin(phi)*sin(theta)*cos(psi)-c" - "os(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...\n cos(phi)*sin(" - "theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];\n\nB_Fg" - " = Lbe * E_Fg;\n\nB_g = B_Fg/m;" + script "function [z_corr, y_cor, x_corr, yaw_corr, pid_y_out, pid_roll_out] = c_controller(set_x, set_y, " + "set_z, set_yaw, ...\n cur_x, cur_y, cur_z, ...\n cur_phi, cur_theta, cur_psi, ...\n cur_phi_d, cur_thet" + "a_d, cur_psi_d, vrpn_id, Tc)\n\nout_z = -1;\nout_y = -1;\nout_x = -1;\nout_yaw = -1;\nc_pid_y = -1;\nc_pid_roll " + "= -1;\n\ncoder.ceval('c_controller', vrpn_id, Tc, set_x, set_y, set_z, set_yaw, ...\n cur_x, " + "cur_y, cur_z, ...\n cur_phi, cur_theta, cur_psi, ...\n cur_phi_d, cur_thet" + "a_d, cur_psi_d, ...\n coder.wref(out_z), coder.wref(out_y), coder.wref(out_x), coder.wref(out" + "_yaw), ...\n coder.wref(c_pid_y), coder.wref(c_pid_roll));\n\nz_corr = out_z;\ny_cor = out_y;" + "\nx_corr = out_x;\npid_y_out = c_pid_y;\npid_roll_out = c_pid_roll;\nyaw_corr = out_yaw;\n" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 84 - ssIdNumber 7 - name "E_Fg" + id 138 + ssIdNumber 4 + name "set_x" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [136 0 139] + } + data { + id 139 + ssIdNumber 5 + name "z_corr" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + linkNode [136 138 140] + } + data { + id 140 + ssIdNumber 6 + name "set_y" scope INPUT_DATA machine 1 props { @@ -8310,17 +16688,17 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [82 0 85] + linkNode [136 139 141] } data { - id 85 - ssIdNumber 11 - name "euler_angles" + id 141 + ssIdNumber 7 + name "set_z" scope INPUT_DATA machine 1 props { array { - size "3" + size "-1" } type { method SF_INHERITED_TYPE @@ -8332,17 +16710,17 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [82 84 86] + linkNode [136 140 142] } data { - id 86 - ssIdNumber 9 - name "B_Fg" - scope OUTPUT_DATA + id 142 + ssIdNumber 8 + name "set_yaw" + scope INPUT_DATA machine 1 props { array { - size "3" + size "-1" } type { method SF_INHERITED_TYPE @@ -8351,16 +16729,16 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [82 85 87] + linkNode [136 141 143] } data { - id 87 - ssIdNumber 12 - name "B_g" - scope OUTPUT_DATA + id 143 + ssIdNumber 9 + name "cur_x" + scope INPUT_DATA machine 1 props { array { @@ -8373,16 +16751,16 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [82 86 88] + linkNode [136 142 144] } data { - id 88 - ssIdNumber 13 - name "m" - scope PARAMETER_DATA + id 144 + ssIdNumber 10 + name "cur_y" + scope INPUT_DATA machine 1 props { array { @@ -8398,94 +16776,34 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [82 87 0] - } - junction { - id 89 - position [23.5747 49.5747 7] - chart 82 - subviewer 82 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [82 0 0] - } - transition { - id 90 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 89 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 82 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 82 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [82 0 0] - } - instance { - id 91 - machine 1 - name "\n\n\n\n\n\n/\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - chart 82 + linkNode [136 143 145] } - chart { - id 92 + data { + id 145 + ssIdNumber 11 + name "cur_z" + scope INPUT_DATA machine 1 - name " /\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 93 0 0] - viewObj 92 - ssIdHighWaterMark 14 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 9 - disableImplicitCasting 1 - eml { - name "complimentaryFilter" - } - firstData 94 - firstTransition 100 - firstJunction 99 - } - state { - id 93 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 92 - treeNode [92 0 0 0] - superState SUBCHART - subviewer 92 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function euler_angles_IMU = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro, prev" - "_euler_angles_IMU)\n\nLOOP_TIME = 6.1*10^-3;\n\nprev_phi = prev_euler_angles_IMU(1);\nprev_theta = prev_euler_an" - "gles_IMU(2);\n\nphi_dot_gyro = euler_angles_gyro(1);\ntheta_dot_gyro = euler_angles_gyro(2);\n\nphi = 0.98 * (pr" - "ev_phi + phi_dot_gyro * LOOP_TIME ) + 0.02 * accel_roll;\ntheta = 0.98 * (prev_theta + theta_dot_gyro * LOOP_TIM" - "E) + 0.02 * accel_pitch;\n\neuler_angles_IMU = [phi; theta];\n" - editorLayout "100 M4x1[10 5 700 500]" + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } + dataType "Inherit: Same as Simulink" + linkNode [136 144 146] } data { - id 94 - ssIdNumber 4 - name "accel_pitch" + id 146 + ssIdNumber 12 + name "cur_phi" scope INPUT_DATA machine 1 props { @@ -8495,16 +16813,19 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [92 0 95] + linkNode [136 145 147] } data { - id 95 + id 147 ssIdNumber 13 - name "accel_roll" + name "cur_theta" scope INPUT_DATA machine 1 props { @@ -8521,32 +16842,34 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [92 94 96] + linkNode [136 146 148] } data { - id 96 - ssIdNumber 5 - name "euler_angles_IMU" - scope OUTPUT_DATA + id 148 + ssIdNumber 14 + name "cur_psi" + scope INPUT_DATA machine 1 props { array { - size "[2,1]" + size "-1" } type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [92 95 97] + linkNode [136 147 149] } data { - id 97 - ssIdNumber 6 - name "euler_angles_gyro" + id 149 + ssIdNumber 15 + name "cur_phi_d" scope INPUT_DATA machine 1 props { @@ -8563,12 +16886,12 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [92 96 98] + linkNode [136 148 150] } data { - id 98 - ssIdNumber 12 - name "prev_euler_angles_IMU" + id 150 + ssIdNumber 16 + name "cur_theta_d" scope INPUT_DATA machine 1 props { @@ -8585,93 +16908,79 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [92 97 0] - } - junction { - id 99 - position [23.5747 49.5747 7] - chart 92 - subviewer 92 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [92 0 0] - } - transition { - id 100 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 99 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 92 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 92 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [92 0 0] + linkNode [136 149 151] } - instance { - id 101 + data { + id 151 + ssIdNumber 17 + name "cur_psi_d" + scope INPUT_DATA machine 1 - name " /\n\n\n\n\n\n\n\n" - chart 92 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [136 150 152] } - chart { - id 102 + data { + id 152 + ssIdNumber 18 + name "y_cor" + scope OUTPUT_DATA machine 1 - name " /\n\n\n\n\n\n\n\n\n\n/\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 103 0 0] - viewObj 102 - ssIdHighWaterMark 15 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 10 - disableImplicitCasting 1 - eml { - name "idealIMU" + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO } - firstData 104 - firstTransition 113 - firstJunction 112 + dataType "Inherit: Same as Simulink" + linkNode [136 151 153] } - state { - id 103 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 102 - treeNode [102 0 0 0] - superState SUBCHART - subviewer 102 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [accelReading,gyroReading] = idealIMU(B_vo_dot, B_vo, B_Omega, B_g, r_oc, g)\n%#codegen\n" - "\na = B_vo_dot + cross(B_Omega,B_vo) ; % body frame acceleration \n\naccelReading = (a - B_g)/g ; % acceleromete" - "r reading (ideal)\n\ngyroReading = B_Omega ; % gyroscope reading (ideal) \n\nend\n\n" - editorLayout "100 M4x1[10 5 700 500]" + data { + id 153 + ssIdNumber 19 + name "x_corr" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO } + dataType "Inherit: Same as Simulink" + linkNode [136 152 154] } data { - id 104 - ssIdNumber 4 - name "B_vo_dot" - scope INPUT_DATA + id 154 + ssIdNumber 20 + name "yaw_corr" + scope OUTPUT_DATA machine 1 props { array { @@ -8680,16 +16989,19 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [102 0 105] + linkNode [136 153 155] } data { - id 105 - ssIdNumber 9 - name "B_vo" + id 155 + ssIdNumber 21 + name "vrpn_id" scope INPUT_DATA machine 1 props { @@ -8706,12 +17018,12 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [102 104 106] + linkNode [136 154 156] } data { - id 106 - ssIdNumber 5 - name "accelReading" + id 156 + ssIdNumber 22 + name "pid_y_out" scope OUTPUT_DATA machine 1 props { @@ -8721,18 +17033,20 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" } complexity SF_COMPLEX_INHERITED frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [102 105 107] + linkNode [136 155 157] } data { - id 107 - ssIdNumber 6 - name "B_Omega" - scope INPUT_DATA + id 157 + ssIdNumber 23 + name "pid_roll_out" + scope OUTPUT_DATA machine 1 props { array { @@ -8745,15 +17059,15 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [102 106 108] + linkNode [136 156 158] } data { - id 108 - ssIdNumber 7 - name "B_g" + id 158 + ssIdNumber 25 + name "Tc" scope INPUT_DATA machine 1 props { @@ -8770,13 +17084,95 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [102 107 109] + linkNode [136 157 0] + } + junction { + id 159 + position [23.5747 49.5747 7] + chart 136 + subviewer 136 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [136 0 0] + } + transition { + id 160 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 159 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 136 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 136 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [136 0 0] + } + instance { + id 161 + machine 1 + name "Control System/MATLAB Function1" + chart 136 + } + chart { + id 162 + machine 1 + name " Sensors /Aeb_c\n\n\n\n\n\n\n\n\n\n1" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 163 0 0] + viewObj 162 + ssIdHighWaterMark 6 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 16 + disableImplicitCasting 1 + eml { + name "angular_body_earth_conversion" + } + firstData 164 + firstTransition 168 + firstJunction 167 + } + state { + id 163 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 162 + treeNode [162 0 0 0] + superState SUBCHART + subviewer 162 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_filtered)\n\n" + "phi = euler_angles_filtered(1);\ntheta = euler_angles_filtered(2);\npsi = NaN;\n\nphi_dot = -1;\ntheta_dot = -1;" + "\npsi_dot = -1;\n\np = gyro_reading(1);\nq = gyro_reading(2);\nr = gyro_reading(3);\n\ncoder.ceval( 'aeb_mat', p" + ", q, r, phi, theta, psi, coder.wref(phi_dot), ...\n coder.wref(theta_dot), coder.wref(psi_dot) );\n\n \neul" + "er_rates_IMU = [phi_dot; theta_dot; psi_dot];\n" + editorLayout "100 M4x1[10 5 700 500]" + } } data { - id 109 - ssIdNumber 8 - name "gyroReading" - scope OUTPUT_DATA + id 164 + ssIdNumber 4 + name "gyro_reading" + scope INPUT_DATA machine 1 props { array { @@ -8785,42 +17181,37 @@ Stateflow { type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [102 108 110] + linkNode [162 0 165] } data { - id 110 - ssIdNumber 10 - name "r_oc" - scope INPUT_DATA + id 165 + ssIdNumber 5 + name "euler_rates_IMU" + scope OUTPUT_DATA machine 1 props { array { - size "-1" + size "[3,1]" } type { method SF_INHERITED_TYPE primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [102 109 111] + linkNode [162 164 166] } data { - id 111 - ssIdNumber 12 - name "g" - scope PARAMETER_DATA + id 166 + ssIdNumber 6 + name "euler_angles_filtered" + scope INPUT_DATA machine 1 props { array { @@ -8836,19 +17227,19 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [102 110 0] + linkNode [162 165 0] } junction { - id 112 + id 167 position [23.5747 49.5747 7] - chart 102 - subviewer 102 + chart 162 + subviewer 162 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [102 0 0] + linkNode [162 0 0] } transition { - id 113 + id 168 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -8856,76 +17247,73 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 112 + id 167 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 102 + chart 162 dataLimits [21.175 25.975 14.625 42.575] - subviewer 102 + subviewer 162 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [102 0 0] + linkNode [162 0 0] } instance { - id 114 + id 169 machine 1 - name " /\n\n\n\n\n\n\n\n\n\n/\n\n\n\n\n\n\n" - chart 102 + name " Sensors /Aeb_c\n\n\n\n\n\n\n\n\n\n1" + chart 162 } chart { - id 115 + id 170 machine 1 - name " /3D Graphical Simulation/MATLAB Function" + name " Sensors /MATLAB Function" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 116 0 0] - viewObj 115 - ssIdHighWaterMark 5 + treeNode [0 171 0 0] + viewObj 170 + ssIdHighWaterMark 7 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 11 + chartFileNumber 17 disableImplicitCasting 1 eml { - name "eigenaxis_ucart" + name "complimentaryFilterC" } - firstData 117 - firstTransition 120 - firstJunction 119 + firstData 172 + firstTransition 177 + firstJunction 176 } state { - id 116 + id 171 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 115 - treeNode [115 0 0 0] + chart 170 + treeNode [170 0 0 0] superState SUBCHART - subviewer 115 + subviewer 170 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" - ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " - "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" - "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " - "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" - "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " - "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" + script "function euler_angles_IMU = complimentaryFilterC(accel_pitch, accel_roll, euler_rates_gyro)\n\ne" + "uler_x = euler_rates_gyro(1);\neuler_y = euler_rates_gyro(2);\n\nfiltered_pitch = -1;\nfiltered_roll = -1;\n\nco" + "der.ceval('compl_filter', accel_pitch, accel_roll, euler_x, euler_y, ...\n coder.wref(filtered_pitch)" + ", coder.wref(filtered_roll));\n\neuler_angles_IMU = [filtered_roll; filtered_pitch];\n" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 117 + id 172 ssIdNumber 4 - name "u" + name "accel_pitch" scope INPUT_DATA machine 1 props { @@ -8939,12 +17327,12 @@ Stateflow { complexity SF_COMPLEX_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [115 0 118] + linkNode [170 0 173] } data { - id 118 + id 173 ssIdNumber 5 - name "y" + name "euler_angles_IMU" scope OUTPUT_DATA machine 1 props { @@ -8959,19 +17347,63 @@ Stateflow { frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [115 117 0] + linkNode [170 172 174] + } + data { + id 174 + ssIdNumber 6 + name "accel_roll" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [170 173 175] + } + data { + id 175 + ssIdNumber 7 + name "euler_rates_gyro" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [170 174 0] } junction { - id 119 + id 176 position [23.5747 49.5747 7] - chart 115 - subviewer 115 + chart 170 + subviewer 170 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [115 0 0] + linkNode [170 0 0] } transition { - id 120 + id 177 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -8979,73 +17411,73 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 119 + id 176 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 115 + chart 170 dataLimits [21.175 25.975 14.625 42.575] - subviewer 115 + subviewer 170 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [115 0 0] + linkNode [170 0 0] } instance { - id 121 + id 178 machine 1 - name " /3D Graphical Simulation/MATLAB Function" - chart 115 + name " Sensors /MATLAB Function" + chart 170 } chart { - id 122 + id 179 machine 1 - name " /\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" + name " Sensors /MATLAB Function1" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 123 0 0] - viewObj 122 + treeNode [0 180 0 0] + viewObj 179 ssIdHighWaterMark 6 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 12 + chartFileNumber 18 disableImplicitCasting 1 eml { - name "angular_body_earth_conversion" + name "angle_IMU_C" } - firstData 124 - firstTransition 128 - firstJunction 127 + firstData 181 + firstTransition 185 + firstJunction 184 } state { - id 123 + id 180 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 122 - treeNode [122 0 0 0] + chart 179 + treeNode [179 0 0 0] superState SUBCHART - subviewer 122 + subviewer 179 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_IMU)\n\nphi =" - " euler_angles_IMU(1);\ntheta = euler_angles_IMU(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta); ...\n" - " 0, cos(phi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)/cos(theta)];\n" - "\n \neuler_rates_IMU = Aeb * gyro_reading;\n " + script "function [accel_pitch, accel_roll] = angle_IMU_C(accel_reading)\n\naccel_x = accel_reading(1);\n" + "accel_y = accel_reading(2);\naccel_z = accel_reading(3);\n\ncalculated_pitch = -1;\ncalculated_roll = -1;\n\ncod" + "er.ceval('angle_accel', accel_x, accel_y, accel_z, coder.wref(calculated_pitch), coder.wref(calculated_roll));\n" + "\naccel_pitch = calculated_pitch;\naccel_roll = calculated_roll;" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 124 + id 181 ssIdNumber 4 - name "gyro_reading" + name "accel_reading" scope INPUT_DATA machine 1 props { @@ -9059,17 +17491,17 @@ Stateflow { complexity SF_COMPLEX_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [122 0 125] + linkNode [179 0 182] } data { - id 125 + id 182 ssIdNumber 5 - name "euler_rates_IMU" + name "accel_pitch" scope OUTPUT_DATA machine 1 props { array { - size "[3,1]" + size "-1" } type { method SF_INHERITED_TYPE @@ -9079,13 +17511,13 @@ Stateflow { frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [122 124 126] + linkNode [179 181 183] } data { - id 126 + id 183 ssIdNumber 6 - name "euler_angles_IMU" - scope INPUT_DATA + name "accel_roll" + scope OUTPUT_DATA machine 1 props { array { @@ -9098,22 +17530,22 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED + frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [122 125 0] + linkNode [179 182 0] } junction { - id 127 + id 184 position [23.5747 49.5747 7] - chart 122 - subviewer 122 + chart 179 + subviewer 179 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [122 0 0] + linkNode [179 0 0] } transition { - id 128 + id 185 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -9121,75 +17553,76 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 127 + id 184 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 122 + chart 179 dataLimits [21.175 25.975 14.625 42.575] - subviewer 122 + subviewer 179 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [122 0 0] + linkNode [179 0 0] } instance { - id 129 + id 186 machine 1 - name " /\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - chart 122 + name " Sensors /MATLAB Function1" + chart 179 } chart { - id 130 + id 187 machine 1 - name " /\n\n\n\n\n\n\n\n\n\n\n\n1" + name " Sensors /Complimentary Filter" windowPosition [422 539.941 189 413] viewLimits [0 156.75 0 153.75] screen [1 1 3600 1200 1.180555555555556] - treeNode [0 131 0 0] - viewObj 130 - ssIdHighWaterMark 10 + treeNode [0 188 0 0] + viewObj 187 + ssIdHighWaterMark 17 decomposition CLUSTER_CHART type EML_CHART - chartFileNumber 13 + chartFileNumber 19 disableImplicitCasting 1 eml { - name "getPitchAndRoll" + name "complimentaryFilter" } - firstData 132 - firstTransition 137 - firstJunction 136 + firstData 189 + firstTransition 195 + firstJunction 194 } state { - id 131 + id 188 labelString "eML_blk_kernel()" position [18 64.5 118 66] fontSize 12 - chart 130 - treeNode [130 0 0 0] + chart 187 + treeNode [187 0 0 0] superState SUBCHART - subviewer 130 + subviewer 187 ssIdNumber 1 type FUNC_STATE decomposition CLUSTER_STATE eml { isEML 1 - script "function [accel_pitch, accel_roll] = getPitchAndRoll(accel_reading, accel_roll_prev)\n\nmag = nor" - "m(accel_reading);\n\nx_accel = accel_reading(1)/mag;\ny_accel = accel_reading(2)/mag;\nz_accel = accel_reading(3" - ")/mag;\n\naccel_pitch = atan(x_accel/sqrt(y_accel^2 + z_accel^2));\n%unwrapped_pitch = unwrap([accel_pitch_prev " - "accel_pitch]);\n%accel_pitch = unwrapped_pitch(2);\n\naccel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^" - "2 + (1/100)*x_accel^2)) );\nunwrapped_roll = unwrap([accel_roll_prev accel_roll]);\naccel_roll = unwrapped_roll(" - "2); \n" + script "%function euler_angles_IMU = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro, pre" + "v_euler_angles_IMU)\nfunction euler_angles_IMU = complimentaryFilter(accel_pitch, accel_roll, euler_rates_gyro," + " prev_euler_angles)\n\nk_gyro = 0.98; \nk_accel = 1-k_gyro; \n\nTs = 0.005; % 5 milliseconds\n\nprev_phi = prev_" + "euler_angles(1);\nprev_theta = prev_euler_angles(2);\n\nprev_phi_dot = euler_rates_gyro(1);\nprev_theta_dot = eu" + "ler_rates_gyro(2);\n\nintegrated_phi_gyro = Ts * prev_phi_dot + prev_phi;\nintegrated_theta_gyro = Ts * prev_the" + "ta_dot + prev_theta;\n\nphi = k_gyro * integrated_phi_gyro + k_accel * accel_roll;\ntheta = k_gyro * integrated_" + "theta_gyro + k_accel * accel_pitch;\n\neuler_angles_IMU = [phi; theta];\n" editorLayout "100 M4x1[10 5 700 500]" } } data { - id 132 + id 189 ssIdNumber 4 - name "accel_reading" + name "accel_pitch" scope INPUT_DATA machine 1 props { @@ -9203,17 +17636,39 @@ Stateflow { complexity SF_COMPLEX_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [130 0 133] + linkNode [187 0 190] } data { - id 133 + id 190 + ssIdNumber 13 + name "accel_roll" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [187 189 191] + } + data { + id 191 ssIdNumber 5 - name "accel_pitch" + name "euler_angles_IMU" scope OUTPUT_DATA machine 1 props { array { - size "-1" + size "[2,1]" } type { method SF_INHERITED_TYPE @@ -9223,13 +17678,13 @@ Stateflow { frame SF_FRAME_NO } dataType "Inherit: Same as Simulink" - linkNode [130 132 134] + linkNode [187 190 192] } data { - id 134 + id 192 ssIdNumber 6 - name "accel_roll" - scope OUTPUT_DATA + name "euler_rates_gyro" + scope INPUT_DATA machine 1 props { array { @@ -9242,15 +17697,15 @@ Stateflow { wordLength "16" } complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO + frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [130 133 135] + linkNode [187 191 193] } data { - id 135 - ssIdNumber 7 - name "accel_roll_prev" + id 193 + ssIdNumber 17 + name "prev_euler_angles" scope INPUT_DATA machine 1 props { @@ -9267,19 +17722,19 @@ Stateflow { frame SF_FRAME_INHERITED } dataType "Inherit: Same as Simulink" - linkNode [130 134 0] + linkNode [187 192 0] } junction { - id 136 + id 194 position [23.5747 49.5747 7] - chart 130 - subviewer 130 + chart 187 + subviewer 187 ssIdNumber 3 type CONNECTIVE_JUNCTION - linkNode [130 0 0] + linkNode [187 0 0] } transition { - id 137 + id 195 labelString "{eML_blk_kernel();}" labelPosition [28.125 13.875 102.544 14.964] fontSize 12 @@ -9287,29 +17742,29 @@ Stateflow { intersection [0 0 1 0 23.5747 14.625 0 0] } dst { - id 136 + id 194 intersection [1 0 -1 0 23.5747 42.5747 0 0] } midPoint [23.5747 24.9468] - chart 130 + chart 187 dataLimits [21.175 25.975 14.625 42.575] - subviewer 130 + subviewer 187 drawStyle SMART slide { sticky BOTH_STICK } executionOrder 1 ssIdNumber 2 - linkNode [130 0 0] + linkNode [187 0 0] } instance { - id 138 + id 196 machine 1 - name " /\n\n\n\n\n\n\n\n\n\n\n\n1" - chart 130 + name " Sensors /Complimentary Filter" + chart 187 } target { - id 139 + id 197 machine 1 name "sfun" description "Default Simulink S-Function Target." diff --git a/controls/model/loggingAnalysis/logAnalysis.m b/controls/model/logAnalysis.m similarity index 68% rename from controls/model/loggingAnalysis/logAnalysis.m rename to controls/model/logAnalysis.m index e1ba18ae230e9a3641771d0879861cb59a09f734..c4f3a1f365deb000fe399bc2a851bd16989a20ff 100644 --- a/controls/model/loggingAnalysis/logAnalysis.m +++ b/controls/model/logAnalysis.m @@ -5,30 +5,30 @@ sim('test_model.slx'); % Determine model time for various sampling times and scale it according to % logged data timescale -indices_40ms = find(pitch_setpoint_model.time > time(1)); -indices_5ms = find(x_command_model.time > time(1)); +indices_40ms = find(pitch_setpoint_model.time >= time(1)); +indices_5ms = find(x_command_model.time >= time(1)); time_model_40ms = pitch_setpoint_model.time(indices_40ms); time_model_5ms = x_command_model.time(indices_5ms); % Pull x control structure data pitch_setpoint_model_data = pitch_setpoint_model.signals.values(indices_40ms); -pitchrate_setpoint_model_data = pitchrate_setpoint_model.signals.values(indices_40ms); +pitchrate_setpoint_model_data = pitchrate_setpoint_model.signals.values(indices_5ms); x_command_model_data = x_command_model.signals.values(indices_5ms); x_position_model_data = x_position_model.signals.values(indices_40ms); % Pull y control structure data roll_setpoint_model_data = roll_setpoint_model.signals.values(indices_40ms); -rollrate_setpoint_model_data = rollrate_setpoint_model.signals.values(indices_40ms); +rollrate_setpoint_model_data = rollrate_setpoint_model.signals.values(indices_5ms); y_command_model_data = y_command_model.signals.values(indices_5ms); y_position_model_data = y_position_model.signals.values(indices_40ms); % Pull z control structure data -z_command_model_data = z_command_model.signals.values(indices_40ms); +z_command_model_data = z_command_model.signals.values(indices_5ms); z_position_model_data = z_position_model.signals.values(indices_40ms); % Pull yaw control structure data yawrate_setpoint_model_data = yawrate_setpoint_model.signals.values(indices_40ms); -yaw_command_model_data = yaw_command_model.signals.values(indices_40ms); +yaw_command_model_data = yaw_command_model.signals.values(indices_5ms); yaw_value_model_data = yaw_value_model.signals.values(indices_40ms); % Pull duty cycle commands from model @@ -37,6 +37,12 @@ PWM1_model = motorCommands.signals.values(indices_5ms, 2); PWM2_model = motorCommands.signals.values(indices_5ms, 3); PWM3_model = motorCommands.signals.values(indices_5ms, 4); +%Pull accelerometer readings from model +pitch_accel = angle_IMU_reading.signals.values(2, 1, indices_5ms); +pitch_accel = reshape(pitch_accel, [length(pitch_accel) , 1] ); +roll_accel = angle_IMU_reading.signals.values(1, 1, indices_5ms); +roll_accel = reshape(roll_accel, [length(roll_accel) , 1] ); + %% Plot x control structure % Plot lateral controller output @@ -51,7 +57,7 @@ legend('Log', 'Model', 'location', 'northwest'); % Plot pitch controller output subplot(2, 2, 2); stairs(time, pitchrate_setpoint,'.-'); hold on; grid minor; -stairs(time_model_40ms, pitchrate_setpoint_model_data, '.-'); hold off; +stairs(time_model_5ms, pitchrate_setpoint_model_data, '.-'); hold off; title('Pitch Controller Output'); xlabel('Time (s)'); ylabel('d\theta/dt (rad/s)'); @@ -79,8 +85,8 @@ legend('Log', 'Model', 'location', 'northwest'); % Plot longitude controller output figure(2); subplot(2, 2, 1); -stairs(time, pitch_setpoint, '.-'); hold on; grid minor; -stairs(time_model_40ms, pitch_setpoint_model_data, '.-'); hold off; +stairs(time, roll_setpoint, '.-'); hold on; grid minor; +stairs(time_model_40ms, roll_setpoint_model_data, '.-'); hold off; title('Longitude Controller Output '); xlabel('Time (s)'); ylabel('\phi (rad)'); @@ -89,7 +95,7 @@ legend('Log', 'Model', 'location', 'northwest'); % Plot roll controller output subplot(2, 2, 2); stairs(time, rollrate_setpoint,'.-'); hold on; grid minor; -stairs(time_model_40ms, rollrate_setpoint_model_data, '.-'); hold off; +stairs(time_model_5ms, rollrate_setpoint_model_data, '.-'); hold off; title('Roll Controller Output'); xlabel('Time (s)'); ylabel('d\phi/dt (rad/s)'); @@ -118,7 +124,7 @@ legend('Log', 'Model', 'location', 'northwest'); % Plot z controller command figure(3); subplot(2, 1, 1); stairs(time, z_command, '.-'); hold on; grid minor; -stairs(time_model_40ms, z_command_model_data, '.-'); hold off; +stairs(time_model_5ms, z_command_model_data, '.-'); hold off; title('Z Command'); xlabel('Time (s)'); ylabel('Command'); @@ -135,7 +141,7 @@ legend('Log', 'Model', 'location', 'northwest'); %% Plot yaw control structure -% Plot roll controller output +% Plot yaw controller output figure(4); subplot(2, 2, 1); stairs(time, yawrate_setpoint,'.-'); hold on; grid minor; stairs(time_model_40ms, yawrate_setpoint_model_data, '.-'); hold off; @@ -147,7 +153,7 @@ legend('Log', 'Model', 'location', 'northwest'); % Plot yaw controller command subplot(2, 2, 2); stairs(time, yaw_command, '.-'); hold on; grid minor; -stairs(time_model_40ms, yaw_command_model_data, '.-'); hold off; +stairs(time_model_5ms, yaw_command_model_data, '.-'); hold off; title('Yaw Command'); xlabel('Time (s)'); ylabel('Command'); @@ -163,7 +169,7 @@ ylabel('Value (rad)'); legend('Log', 'Model', 'location', 'northwest'); %% Plot PWM Commands -figure(5); subplot(2, 2, 1); +figure(5); ax1 = subplot(2, 2, 1); stairs(time, PWM0,'.-'); hold on; grid minor; stairs(time_model_5ms, PWM0_model, '.-'); hold off; title('PWM0 Value'); @@ -171,7 +177,7 @@ xlabel('Time (s)'); ylabel('PWM0 Command'); legend('Log', 'Model', 'location', 'northwest'); -subplot(2, 2, 2); +ax2 = subplot(2, 2, 2); stairs(time, PWM1,'.-'); hold on; grid minor; stairs(time_model_5ms, PWM1_model, '.-'); hold off; title('PWM1 Value'); @@ -179,18 +185,68 @@ xlabel('Time (s)'); ylabel('PWM1 Command'); legend('Log', 'Model', 'location', 'northwest'); -subplot(2, 2, 3); +ax3 = subplot(2, 2, 3); stairs(time, PWM2,'.-'); hold on; grid minor; stairs(time_model_5ms, PWM2_model, '.-'); hold off; title('PWM2 Value'); xlabel('Time (s)'); ylabel('PWM2 Command'); legend('Log', 'Model', 'location', 'northwest'); - -subplot(2, 2, 4); + +ax4 = subplot(2, 2, 4); stairs(time, PWM3,'.-'); hold on; grid minor; stairs(time_model_5ms, PWM3_model, '.-'); hold off; title('PWM3 Value'); xlabel('Time (s)'); ylabel('PWM3 Command'); -legend('Log', 'Model', 'location', 'northwest'); \ No newline at end of file +legend('Log', 'Model', 'location', 'northwest'); + +linkaxes([ax1, ax2, ax3, ax4], 'xy'); + +%% Plot output of complimentary filter + +figure(8); subplot(2, 1, 1); +stairs(time, pitch_measured_VRPN * (180/pi), '.-'); hold on; grid minor; +stairs(time, pitch_measured_IMU * (180/pi), '.-'); +stairs(time_model_5ms, pitch_accel * (180/pi), '.-'); hold off; +title('Pitch Complementary Filter Output'); +xlabel('Time (s)'); +ylabel('Pitch Angle (degrees)'); +legend('VRPN','IMU', 'Model', 'location', 'northwest'); + +subplot(2, 1, 2); +stairs(time, roll_measured_VRPN * (180/pi), '.-'); hold on; grid minor; +stairs(time, roll_measured_IMU * (180/pi), '.-'); +stairs(time_model_5ms, roll_accel * (180/pi), '.-'); hold off; +title('Roll Complementary Filter Output'); +xlabel('Time (s)'); +ylabel('Roll Angle (degrees)'); +legend('VRPN','IMU', 'Model', 'location', 'northwest'); + +%% Plot VRPN Position + +figure(9); ax1 = subplot(3, 1, 1); +stairs(time, x_position, '.-'); hold on; grid minor; +stairs(time_model_40ms, x_position_model_data, '.-'); +title('X position'); +xlabel('Time (s)'); +ylabel('X position'); +legend('X position', 'X position model', 'X setpoint'); + +ax2 = subplot(3, 1, 2); +stairs(time, y_position, '.-'); hold on; grid minor; +stairs(time_model_40ms, y_position_model_data, '.-'); +title('Y position'); +xlabel('Time (s)'); +ylabel('Y position'); +legend('Y position', 'Y position model', 'Y setpoint'); + +ax3 = subplot(3, 1, 3); +stairs(time, y_position, '.-'); hold on; grid minor; +stairs(time_model_40ms, y_position_model_data, '.-'); +title('Z position'); +xlabel('Time (s)'); +ylabel('Z position'); +legend('Z position', 'Z position model', 'Y setpoint'); + +linkaxes([ax1, ax2, ax3], 'x'); diff --git a/controls/model/loggingAnalysis/logFiles/logData.csv b/controls/model/loggingAnalysis/logFiles/logData.csv deleted file mode 100644 index ec82bdd6374c782adf567e0a0539429ce8758c2d..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/logFiles/logData.csv +++ /dev/null @@ -1,404 +0,0 @@ -time,accel_x,accel_y,accel_z,gyro_x,gyro_y,gyro_z,Altitude PID-Correction,X pos PID-Correction,Y pos PID-Correction,Pitch PID-Correction,Roll PID-Correction,Yaw PID-Correction,Pitch Rate PID-Correction,Roll Rate PID-Correction,Yaw Rate PID-Correction,Pitch-Constant,Roll-Constant,Yaw-Constant,VRPN X-Constant,VRPN Y-Constant,VRPN Alt-Constant,VRPN Pitch-Constant,VRPN Roll-Constant,X Setpoint-Constant,Y Setpoint-Constant,Alt Setpoint-Constant,Signal Mixer-PWM 0,Signal Mixer-PWM 1,Signal Mixer-PWM 2,Signal Mixer-PWM 3 -6.301439,-0.011668,-0.001742,-1.004309,-0.157827,-0.095945,-0.026303,0,0.00439,0.004135,0.011777,0.028141,0.16461,197.68364,341.272278,1948.421997,0,0,-0.179351,0.092536,0.332093,-0.062224,-0.007387,-0.024006,0.089533,0.334481,0,148977,153269,153557,150055 -6.30644,-0.018504,-0.001498,-0.996984,-0.157827,-0.105523,-0.032688,0,0.00439,0.004135,0.011777,0.028141,0.16461,215.260483,341.272278,2013.589722,0,0,-0.179351,0.092536,0.332093,-0.062224,-0.007387,-0.024006,0.089533,0.334481,0,148894,153352,153604,150007 -6.311441,-0.024852,-0.010287,-1.003576,-0.168469,-0.095945,-0.031624,0,0.164289,0.093666,0.208444,0.068839,1.798129,558.591187,435.488098,18674.09375,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,131796,170262,170015,133784 -6.316442,-0.035594,-0.013217,-0.994055,-0.17379,-0.124679,-0.034817,0,0.164289,0.093666,0.208444,0.068839,1.798129,611.321777,445.253021,18706.67773,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,131701,170337,170005,133814 -6.321444,-0.036082,-0.0181,-0.995764,-0.181239,-0.105523,-0.035881,0,0.164289,0.093666,0.208444,0.068839,1.798129,576.16803,458.92392,18717.53906,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132382,170969,170735,134452 -6.326445,-0.023631,-0.004672,-1.007727,-0.192946,-0.142771,-0.024175,0,0.164289,0.093666,0.208444,0.068839,1.798129,644.522461,480.406708,18598.06445,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132412,170897,170568,134661 -6.331446,-0.028514,-0.006137,-1.014318,-0.192946,-0.120423,-0.013532,0,0.164289,0.093666,0.208444,0.068839,1.798129,603.509827,480.406708,18489.45117,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132561,170747,170501,134729 -6.336447,-0.018504,-0.002719,-1.027502,-0.200396,-0.141707,0.004559,0,0.164289,0.093666,0.208444,0.068839,1.798129,642.569519,494.077606,18304.81055,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132693,170588,170291,134966 -6.341448,-0.034129,-0.004184,-1.035803,-0.203588,-0.140643,0.019459,0,0.164289,0.093666,0.208444,0.068839,1.798129,640.616516,499.936554,18152.75195,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,133681,171268,170987,135962 -6.346449,-0.026072,-0.009799,-1.050207,-0.200396,-0.138514,0.040743,0,-0.221409,-0.122364,-0.211557,-0.097072,-0.963148,-134.041611,189.611008,-10245.51367,0,0,-0.179668,0.092758,0.331645,-0.062624,-0.009852,-0.025292,0.089533,0.334481,0,163164,142405,143053,163276 -6.35145,-0.036326,-0.002963,-1.056555,-0.19401,-0.152349,0.055642,0,0.074765,0.045207,0.080767,0.080169,0.04503,427.796539,503.15152,-108.308807,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152152,152791,152942,154014 -6.356451,-0.029979,-0.004916,-1.060705,-0.178047,-0.13745,0.073734,0,0.074765,0.045207,0.080767,0.080169,0.04503,400.454773,473.856781,-292.950409,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152393,152608,152755,154142 -6.361452,-0.034861,0.00485,-1.056066,-0.169533,-0.141707,0.083312,0,0.074765,0.045207,0.080767,0.080169,0.04503,408.266724,458.23288,-390.701904,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152499,152534,152634,154232 -6.366453,-0.031932,-0.001742,-1.070471,-0.162083,-0.1449,0.088633,0,0.074765,0.045207,0.080767,0.080169,0.04503,414.125671,444.562012,-445.008301,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152808,152746,152807,154525 -6.371454,-0.028758,0.003629,-1.069738,-0.151441,-0.138514,0.091826,0,0.074765,0.045207,0.080767,0.080169,0.04503,402.407745,425.032196,-477.592133,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152872,152721,152767,154527 -6.376455,-0.037303,0.00192,-1.069006,-0.148248,-0.141707,0.093954,0,0.074765,0.045207,0.080767,0.080169,0.04503,408.266724,419.173218,-499.314606,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152893,152711,152733,154548 -6.381456,-0.033641,0.005582,-1.070471,-0.134414,-0.143836,0.091826,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,229.861832,296.212311,-968.647034,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153664,152187,152319,154716 -6.386457,-0.037059,-0.005893,-1.073889,-0.128028,-0.141707,0.09289,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,225.955856,284.494385,-979.50824,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153655,152147,152265,154675 -6.391459,-0.02949,-0.000766,-1.068762,-0.120579,-0.151285,0.085441,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,243.532684,270.823517,-903.47937,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153575,152255,152309,154603 -6.39646,-0.036082,-0.006137,-1.071691,-0.114193,-0.142771,0.082248,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,227.908844,259.105591,-870.895569,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153569,152283,152346,154543 -6.401461,-0.037791,-0.002475,-1.058752,-0.112065,-0.158735,0.07267,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,257.203583,255.199631,-773.144104,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153446,152414,152410,154471 -6.406462,-0.047312,-0.016391,-1.064611,-0.106744,-0.145964,0.067349,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,233.767792,245.434708,-718.837769,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153425,152455,152478,154384 -6.411463,-0.045359,-0.010043,-1.056066,-0.102487,-0.150221,0.063092,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,241.579727,237.622787,-675.392639,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153424,152556,152548,154382 -6.416464,-0.042674,-0.017855,-1.061926,-0.095037,-0.138514,0.054578,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,220.096909,223.951889,-588.502441,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153372,152635,152643,154260 -6.421465,-0.040721,-0.007113,-1.056799,-0.093973,-0.135322,0.047128,0,0.009461,0.009245,0.035455,0.06162,-0.021322,313.395386,285.532745,-698.58728,0,0,-0.170691,0.090296,0.329721,-0.067473,-0.025993,-0.052375,0.089533,0.334481,0,153327,152557,152501,154525 -6.426466,-0.037791,-0.009555,-1.059729,-0.101423,-0.139579,0.036486,0,0.009461,0.009245,0.035455,0.06162,-0.021322,321.207306,299.203644,-589.974548,0,0,-0.170691,0.090296,0.329721,-0.067473,-0.025993,-0.052375,0.089533,0.334481,0,153197,152660,152616,154438 -6.431467,-0.039988,-0.006625,-1.061437,-0.100358,-0.127872,0.027972,0,0.000065,0.005708,0.019697,0.050031,0.028214,270.807312,275.9823,2.464528,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152620,153167,153177,153714 -6.436468,-0.049021,-0.002719,-1.058508,-0.109936,-0.124679,0.023715,0,0.000065,0.005708,0.019697,0.050031,0.028214,264.948364,293.559143,45.909622,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152565,153187,153244,153682 -6.441469,-0.044383,-0.005893,-1.060949,-0.108872,-0.118294,0.01733,0,0.000065,0.005708,0.019697,0.050031,0.028214,253.230469,291.606171,111.077271,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152514,153242,153319,153603 -6.44647,-0.051951,0.000455,-1.065832,-0.120579,-0.100202,0.012009,0,0.000065,0.005708,0.019697,0.050031,0.028214,220.029739,313.088989,165.383636,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152471,153242,153428,153537 -6.451471,-0.040477,-0.00516,-1.08048,-0.119514,-0.092753,0.002431,0,0.000065,0.005708,0.019697,0.050031,0.028214,206.358841,311.136017,263.135101,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152400,153339,153548,153435 -6.456472,-0.044871,-0.001742,-1.072668,-0.120579,-0.075725,-0.003954,0,0.000065,0.005708,0.019697,0.050031,0.028214,175.111115,313.088989,328.302734,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152364,153371,153647,153340 -6.461473,-0.036814,0.000943,-1.078771,-0.128028,-0.076789,-0.011404,0,-0.001065,0.004985,0.022011,0.050641,-0.005194,181.309982,327.879913,63.379238,0,0,-0.170989,0.090393,0.32806,-0.070697,-0.023076,-0.045656,0.089533,0.334481,0,152608,153097,153390,153626 -6.466475,-0.040965,0.000943,-1.066564,-0.124836,-0.065083,-0.019918,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,159.491013,329.699799,-109.653984,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152801,152901,153241,153779 -6.471476,-0.043162,-0.007357,-1.068518,-0.135478,-0.060826,-0.026303,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,151.679077,349.229645,-44.486332,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152724,152938,153334,153726 -6.476477,-0.046092,-0.003695,-1.051428,-0.132285,-0.053376,-0.033753,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,138.008179,343.370697,31.542593,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152706,153045,153455,153668 -6.481478,-0.047557,-0.010043,-1.046301,-0.133349,-0.055505,-0.036945,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,141.914154,345.3237,64.126389,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152667,153079,153486,153642 -6.486479,-0.037547,0.001187,-1.041906,-0.130157,-0.054441,-0.045459,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,139.961166,339.464722,151.016571,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152588,153170,153569,153547 -6.49148,-0.042186,-0.007357,-1.054357,-0.126964,-0.06189,-0.047588,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,153.63205,333.605774,172.73912,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152559,153211,153571,153533 -6.496481,-0.034861,0.004361,-1.053137,-0.126964,-0.072532,-0.056101,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,173.161896,333.605774,259.629303,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152472,153338,153659,153486 -6.501482,-0.038035,0.003141,-1.043127,-0.122707,-0.081046,-0.061423,0,0.005803,0.011575,0.0352,0.069559,0.084575,213.3255,352.831543,1490.022461,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,151182,154589,154868,152315 -6.506483,-0.035838,0.010709,-1.046789,-0.130157,-0.093817,-0.066744,0,0.005803,0.011575,0.0352,0.069559,0.084575,236.761292,366.502441,1544.328857,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,151091,154653,154913,152297 -6.511484,-0.039012,0.009488,-1.04923,-0.126964,-0.095945,-0.073129,0,0.005803,0.011575,0.0352,0.069559,0.084575,240.667267,360.643463,1609.49646,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,151028,154728,154968,152230 -6.516485,-0.0395,0.007047,-1.04923,-0.133349,-0.102331,-0.076322,0,0.005803,0.011575,0.0352,0.069559,0.084575,252.385178,372.361389,1642.080322,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150972,154761,155001,152221 -6.521486,-0.039988,0.010465,-1.030676,-0.128028,-0.102331,-0.082707,0,0.005803,0.011575,0.0352,0.069559,0.084575,252.385178,362.596466,1707.247925,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150843,154763,154983,152073 -6.526487,-0.036814,0.00192,-1.027746,-0.1259,-0.107652,-0.081643,0,0.005803,0.011575,0.0352,0.069559,0.084575,262.150085,358.690491,1696.386597,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150848,154765,154958,152090 -6.531488,-0.026316,0.007535,-1.025549,-0.128028,-0.112973,-0.086964,0,0.005803,0.011575,0.0352,0.069559,0.084575,271.915009,362.596466,1750.692993,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150780,154826,155007,152049 -6.536489,-0.029246,-0.008822,-1.033605,-0.119514,-0.121487,-0.089092,0,0.005414,0.011035,0.034504,0.069701,0.166096,286.262482,347.233307,2604.397705,0,0,-0.178617,0.093033,0.320763,-0.081838,-0.02909,-0.058666,0.089533,0.334481,0,149928,155709,155831,151195 -6.541491,-0.033641,0.002164,-1.006262,-0.11845,-0.127872,-0.091221,0,0.000548,0.009802,0.035223,0.071678,0.133144,299.299255,348.908173,2289.823975,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150286,155465,155564,151583 -6.546492,-0.030955,-0.009799,-1.004553,-0.109936,-0.141707,-0.092285,0,0.000548,0.009802,0.035223,0.071678,0.133144,324.688049,333.284302,2300.685303,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150266,155517,155534,151582 -6.551493,-0.038035,-0.005893,-1.004797,-0.111001,-0.149157,-0.090157,0,0.000548,0.009802,0.035223,0.071678,0.133144,338.358948,335.237274,2278.962646,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150272,155507,155500,151619 -6.556494,-0.028758,-0.007113,-1.008703,-0.106744,-0.162992,-0.094414,0,0.000548,0.009802,0.035223,0.071678,0.133144,363.747711,327.425354,2322.407959,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150211,155583,155511,151593 -6.561495,-0.035105,-0.001254,-0.99552,-0.105679,-0.174698,-0.094414,0,0.000548,0.009802,0.035223,0.071678,0.133144,385.23056,325.472351,2322.407959,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150187,155603,155483,151609 -6.566496,-0.026805,0.003141,-0.992834,-0.09823,-0.186405,-0.096542,0,0.000548,0.009802,0.035223,0.071678,0.133144,406.713379,311.801483,2344.130371,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150158,155660,155470,151595 -6.571497,-0.027049,0.004361,-0.988684,-0.095037,-0.200239,-0.094414,0,0.000548,0.009802,0.035223,0.071678,0.133144,432.102142,305.942535,2322.407959,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150160,155669,155417,151636 -6.576498,-0.027537,0.006559,-0.992834,-0.089716,-0.208753,-0.096542,0,0.000548,0.009802,0.035223,0.071678,0.133144,447.726013,296.177612,2344.130371,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150132,155716,155413,151620 -6.581499,-0.019969,0.003141,-0.99259,-0.093973,-0.226845,-0.096542,0,0.00944,0.014183,0.046678,0.080704,0.234826,501.948853,320.55368,3381.871826,0,0,-0.182364,0.094601,0.317227,-0.086471,-0.037239,-0.066521,0.089533,0.334481,0,149016,156784,156421,150661 -6.5865,-0.037303,-0.003939,-0.983557,-0.097166,-0.232166,-0.099735,0,0.002105,0.01083,0.043179,0.075637,0.213407,505.291534,317.114746,3195.86377,0,0,-0.183428,0.09539,0.314939,-0.089857,-0.041074,-0.064807,0.089533,0.334481,0,149166,156569,156192,150811 -6.591501,-0.025096,0.00485,-0.985021,-0.101423,-0.251322,-0.100799,0,-0.002989,0.008261,0.042601,0.07447,0.141009,539.385376,322.783813,2467.846191,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149854,155869,155436,151579 -6.596502,-0.04658,-0.001742,-0.969641,-0.105679,-0.253451,-0.096542,0,-0.002989,0.008261,0.042601,0.07447,0.141009,543.291321,330.595734,2424.401123,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149886,155822,155396,151634 -6.601503,-0.023631,0.004117,-0.987707,-0.115257,-0.269414,-0.094414,0,-0.002989,0.008261,0.042601,0.07447,0.141009,572.586121,348.172607,2402.678711,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149861,155812,155363,151703 -6.606504,-0.032908,0.007779,-0.968664,-0.1259,-0.269414,-0.090157,0,-0.002989,0.008261,0.042601,0.07447,0.141009,572.586121,367.702423,2359.233643,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149924,155788,155378,151805 -6.611506,-0.024119,-0.001498,-0.977697,-0.137606,-0.278992,-0.086964,0,-0.002989,0.008261,0.042601,0.07447,0.141009,590.162964,389.185272,2326.649658,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149918,155751,155349,151876 -6.616507,-0.02827,0.010465,-0.974035,-0.15357,-0.283249,-0.088028,0,-0.002989,0.008261,0.042601,0.07447,0.141009,597.974915,418.480011,2337.510986,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149870,155741,155382,151902 -6.621508,-0.037303,-0.018344,-0.983068,-0.159955,-0.280056,-0.083771,0,0.009291,0.01657,0.063571,0.083133,0.245788,630.598633,446.09549,3363.417725,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148783,156771,156402,150937 -6.626509,-0.032664,0.00485,-0.979895,-0.196139,-0.298148,-0.081643,0,0.009291,0.01657,0.063571,0.083133,0.245788,663.799316,512.496948,3341.695312,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148706,156716,156414,151058 -6.63151,-0.041697,-0.014682,-0.971594,-0.190818,-0.286442,-0.080579,0,0.009291,0.01657,0.063571,0.083133,0.245788,642.316467,502.732025,3330.833984,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148705,156651,156372,150995 -6.636511,-0.026805,0.015836,-0.977453,-0.227001,-0.292827,-0.079514,0,0.009291,0.01657,0.063571,0.083133,0.245788,654.034424,569.133484,3319.972656,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148637,156585,156416,151084 -6.641512,-0.03242,0.00607,-0.965002,-0.220616,-0.282185,-0.076322,0,0.009291,0.01657,0.063571,0.083133,0.245788,634.504578,557.415588,3287.388916,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148701,156545,156391,151085 -6.646513,-0.020945,0.006803,-0.977209,-0.24935,-0.283249,-0.073129,0,0.009291,0.01657,0.063571,0.083133,0.245788,636.457581,610.146118,3254.804932,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148679,156462,156409,151172 -6.651514,-0.034617,0.005094,-0.967443,-0.247221,-0.278992,-0.073129,0,0.009291,0.01657,0.063571,0.083133,0.245788,628.64563,606.240173,3254.804932,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148699,156466,156421,151169 -6.656515,-0.037791,-0.016146,-0.971838,-0.261056,-0.263029,-0.069936,0,0.009291,0.01657,0.063571,0.083133,0.245788,599.350891,631.628906,3222.221191,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148735,156378,156443,151197 -6.661516,-0.043895,0.000455,-0.97843,-0.280212,-0.265157,-0.068872,0,0.001518,0.01505,0.059947,0.084196,0.232589,596.605652,668.733826,3076.653809,0,0,-0.18527,0.097699,0.306837,-0.098775,-0.058429,-0.069146,0.089533,0.334481,0,148847,156193,156337,151377 -6.666517,-0.031199,-0.022738,-0.9755,-0.265313,-0.24813,-0.067808,0,0.009062,0.019296,0.073325,0.094303,0.289687,589.908203,659.939758,3648.523926,0,0,-0.187304,0.099082,0.303287,-0.101578,-0.064263,-0.075007,0.089533,0.334481,0,148290,156767,156907,150790 -6.671518,-0.024363,0.010709,-0.959143,-0.295112,-0.250258,-0.065679,0,-0.00577,0.010068,0.062218,0.085465,0.166748,573.432434,698.404846,2372.109375,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149585,155476,155726,152128 -6.676519,-0.032664,0.011197,-0.952062,-0.285534,-0.249194,-0.063551,0,-0.00577,0.010068,0.062218,0.085465,0.166748,571.479431,680.827942,2350.386963,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149626,155470,155688,152130 -6.68152,-0.034617,0.010221,-0.956457,-0.303625,-0.238552,-0.05823,0,-0.00577,0.010068,0.062218,0.085465,0.166748,551.949585,714.028687,2296.080566,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149666,155363,155687,152198 -6.686522,-0.024119,0.023893,-0.961584,-0.299369,-0.238552,-0.057166,0,-0.00577,0.010068,0.062218,0.085465,0.166748,551.949585,706.216736,2285.219238,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149685,155359,155668,152201 -6.691523,-0.025584,0.012174,-0.959631,-0.303625,-0.228974,-0.055037,0,-0.00577,0.010068,0.062218,0.085465,0.166748,534.372742,714.028687,2263.496826,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149717,155312,155672,152213 -6.696524,-0.023387,0.017301,-0.973791,-0.318525,-0.247065,-0.05078,0,-0.00577,0.010068,0.062218,0.085465,0.166748,567.573486,741.370483,2220.051758,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149665,155240,155587,152282 -6.701525,-0.044627,0.001432,-0.970617,-0.315332,-0.235359,-0.05078,0,0.01477,0.024073,0.084526,0.103699,0.305827,587.028076,768.973633,3639.465576,0,0,-0.18704,0.099813,0.300079,-0.104311,-0.069756,-0.079627,0.089533,0.334481,0,148198,156651,157015,150910 -6.706526,-0.043895,-0.00101,-0.965246,-0.33236,-0.250258,-0.048652,0,0.01477,0.024073,0.084526,0.103699,0.305827,614.369873,800.221375,3617.74292,0,0,-0.18704,0.099813,0.300079,-0.104311,-0.069756,-0.079627,0.089533,0.334481,0,148161,156625,156997,150990 -6.711527,-0.024852,0.009977,-0.962561,-0.334488,-0.257708,-0.053973,0,0.01477,0.024073,0.084526,0.103699,0.305827,628.04071,804.127319,3672.049316,0,0,-0.18704,0.099813,0.300079,-0.104311,-0.069756,-0.079627,0.089533,0.334481,0,148089,156689,157042,150954 -6.716528,-0.027293,-0.002719,-0.966223,-0.350451,-0.266221,-0.05078,0,0.001642,0.017462,0.083061,0.110254,0.250542,640.975525,845.450562,3075.240234,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148623,156055,156464,151596 -6.721529,-0.015818,0.005094,-0.977697,-0.362158,-0.298148,-0.051845,0,0.001642,0.017462,0.083061,0.110254,0.250542,699.565063,866.933411,3086.101562,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148532,156103,156438,151665 -6.72653,-0.062693,-0.018832,-0.974035,-0.375993,-0.28857,-0.045459,0,0.001642,0.017462,0.083061,0.110254,0.250542,681.988159,892.322205,3020.933838,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148589,155995,156416,151738 -6.731531,-0.036326,-0.005648,-0.977697,-0.40047,-0.327947,-0.041202,0,0.001642,0.017462,0.083061,0.110254,0.250542,754.248596,937.240845,2977.48877,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148516,155979,156345,151899 -6.736532,-0.037547,-0.012973,-0.959631,-0.408984,-0.315176,-0.042266,0,0.001642,0.017462,0.083061,0.110254,0.250542,730.812805,952.864685,2988.350098,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148512,155951,156395,151880 -6.741533,-0.016062,0.003141,-0.969152,-0.431332,-0.34391,-0.036945,0,0.001642,0.017462,0.083061,0.110254,0.250542,783.543335,993.87738,2934.043701,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148510,155945,156366,152065 -6.746534,-0.023387,0.018277,-0.961096,-0.439846,-0.36413,-0.039074,0,0.016426,0.030313,0.100886,0.125293,0.357282,853.361023,1037.10022,4045.128906,0,0,-0.189161,0.10253,0.291828,-0.109526,-0.084459,-0.09498,0.089533,0.334481,0,147286,157083,157450,151067 -6.751535,-0.045115,-0.007113,-0.953771,-0.463259,-0.369451,-0.034817,0,0.003708,0.019999,0.098309,0.130303,0.285718,858.398193,1089.259399,3271.313965,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,148003,156262,156724,151898 -6.756536,-0.053416,0.01901,-0.946691,-0.487736,-0.394993,-0.033753,0,0.003708,0.019999,0.098309,0.130303,0.285718,905.269836,1134.177979,3260.452637,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147922,156253,156711,152000 -6.761538,-0.054881,-0.009799,-0.948645,-0.48348,-0.387543,-0.032688,0,0.003708,0.019999,0.098309,0.130303,0.285718,891.598938,1126.366089,3249.591309,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147927,156209,156679,151963 -6.766539,-0.042186,0.019986,-0.955236,-0.514342,-0.403507,-0.022046,0,0.003708,0.019999,0.098309,0.130303,0.285718,920.893677,1183.002563,3140.97876,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147950,156073,156598,152157 -6.77154,-0.032176,-0.003207,-0.949621,-0.484544,-0.407763,-0.026303,0,0.003708,0.019999,0.098309,0.130303,0.285718,928.705627,1128.31897,3184.423828,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147953,156179,156579,152067 -6.776541,-0.03242,0.007535,-0.948889,-0.517535,-0.413085,-0.022046,0,0.003708,0.019999,0.098309,0.130303,0.285718,938.47052,1188.861572,3140.97876,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147926,156085,156586,152181 -6.781542,-0.046336,0.002896,-0.942541,-0.495186,-0.429048,-0.020982,0,0.010053,0.029031,0.117675,0.152133,0.274712,1003.303772,1187.90979,3017.791016,0,0,-0.188678,0.107048,0.27738,-0.115865,-0.107623,-0.123102,0.089533,0.334481,0,147982,156025,156394,152365 -6.786543,-0.04951,-0.002475,-0.939367,-0.514342,-0.427984,-0.017789,0,0.010053,0.029031,0.117675,0.152133,0.274712,1001.350769,1223.063477,2985.207275,0,0,-0.188678,0.107048,0.27738,-0.115865,-0.107623,-0.123102,0.089533,0.334481,0,147982,155955,156398,152431 -6.791544,-0.056102,0.009,-0.935949,-0.499443,-0.435433,-0.015661,0,0.007036,0.02832,0.120421,0.157578,0.272034,1020.060364,1205.712646,2936.161133,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148030,155942,156313,152481 -6.796545,-0.044383,-0.002963,-0.931555,-0.497314,-0.434369,-0.015661,0,0.007036,0.02832,0.120421,0.157578,0.272034,1018.107422,1201.806641,2936.161133,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148035,155944,156311,152475 -6.801546,-0.04658,0.012418,-0.939123,-0.491993,-0.440754,-0.008211,0,0.007036,0.02832,0.120421,0.157578,0.272034,1029.825317,1192.041748,2860.132324,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148110,155889,156214,152553 -6.806547,-0.037059,-0.000521,-0.946203,-0.471773,-0.436498,-0.011404,0,0.007036,0.02832,0.120421,0.157578,0.272034,1022.013367,1154.935181,2892.716064,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148165,155994,156260,152519 -6.811548,-0.04365,0.009488,-0.944494,-0.472837,-0.432241,-0.005019,0,0.007036,0.02832,0.120421,0.157578,0.272034,1014.201416,1156.888062,2827.548584,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148236,155919,156205,152578 -6.816549,-0.041453,0.011686,-0.953771,-0.454745,-0.443947,-0.007147,0,0.007036,0.02832,0.120421,0.157578,0.272034,1035.684204,1123.687378,2849.270996,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148226,155996,156172,152545 -6.82155,-0.042186,0.027066,-0.944982,-0.445167,-0.418406,-0.00289,0,0.007036,0.02832,0.120421,0.157578,0.272034,988.812683,1106.110474,2805.825928,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148334,155923,156158,152524 -6.826551,-0.038035,0.025846,-0.953527,-0.421754,-0.433305,-0.001826,0,0.009767,0.030146,0.137926,0.172346,0.237777,1048.277588,1090.246216,2445.338379,0,0,-0.187034,0.110458,0.26592,-0.119144,-0.128159,-0.1422,0.089533,0.334481,0,148645,155632,155716,152922 -6.831553,-0.035105,0.031949,-0.944494,-0.404727,-0.409892,-0.000762,0,0.00815,0.030216,0.139942,0.175236,0.206208,1009.01239,1064.303345,2112.29248,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149043,155286,155396,153190 -6.836554,-0.041941,0.021207,-0.95548,-0.378121,-0.421598,0.002431,0,0.00815,0.030216,0.139942,0.175236,0.206208,1030.495239,1015.478699,2079.70874,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149103,155323,155293,153195 -6.841555,-0.051707,0.027311,-0.956213,-0.362158,-0.388607,0.001367,0,0.00815,0.030216,0.139942,0.175236,0.206208,969.952698,986.183899,2090.569824,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149182,155303,155335,153094 -6.846556,-0.047068,0.010221,-0.967443,-0.327038,-0.387543,0.007752,0,0.00815,0.030216,0.139942,0.175236,0.206208,967.999756,921.735474,2025.402222,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149313,155300,155208,153093 -6.851557,-0.048289,0.015348,-0.97135,-0.314268,-0.356681,0.012009,0,0.00815,0.030216,0.139942,0.175236,0.206208,911.36322,898.299683,1981.957153,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149397,155184,155157,153016 -6.856558,-0.039744,0.002164,-0.970373,-0.271699,-0.348167,0.010945,0,0.00815,0.030216,0.139942,0.175236,0.206208,895.73938,820.180298,1992.818481,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149480,155257,155106,152912 -6.861559,-0.044627,0.00485,-0.968176,-0.268506,-0.32369,0.015202,0,0.014863,0.036434,0.152626,0.181732,0.251648,874.097656,826.241211,2413.12085,0,0,-0.186478,0.113851,0.256189,-0.121182,-0.137764,-0.145298,0.089533,0.334481,0,149075,155649,155554,152476 -6.86656,-0.04365,0.002652,-0.957189,-0.233387,-0.315176,0.014137,0,0.000644,0.026298,0.142909,0.177613,0.083573,840.642029,754.234802,708.641296,0,0,-0.183068,0.114275,0.253368,-0.121638,-0.142265,-0.151315,0.089533,0.334481,0,150885,153984,153811,154075 -6.871561,-0.039988,0.008268,-0.952062,-0.22168,-0.297084,0.016266,0,0.016514,0.039456,0.161102,0.189806,0.175019,840.82782,755.126343,1620.19873,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150615,155537,155366,153807 -6.876562,-0.046336,0.009977,-0.943762,-0.192946,-0.281121,0.013073,0,0.016514,0.039456,0.161102,0.189806,0.175019,811.533081,702.395813,1652.782593,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150665,155593,155375,153693 -6.881563,-0.042186,0.009488,-0.942053,-0.171661,-0.271543,0.015202,0,0.016514,0.039456,0.161102,0.189806,0.175019,793.956238,663.336121,1631.060059,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150743,155593,155332,153658 -6.886564,-0.052684,0.007779,-0.927893,-0.150377,-0.252387,0.015202,0,0.016514,0.039456,0.161102,0.189806,0.175019,758.802551,624.276489,1631.060059,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150817,155597,155328,153584 -6.891565,-0.043406,0.015592,-0.929846,-0.128028,-0.24813,0.015202,0,0.016514,0.039456,0.161102,0.189806,0.175019,750.990601,583.263794,1631.060059,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,151114,155878,155543,153783 -6.896566,-0.047068,0.014615,-0.928625,-0.109936,-0.216203,0.014137,0,0.016514,0.039456,0.161102,0.189806,0.175019,692.401062,550.063049,1641.921265,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,151195,155864,155579,153680 -6.901567,-0.013377,0.025113,-0.932287,-0.086523,-0.228974,0.008816,0,0.016514,0.039456,0.161102,0.189806,0.175019,715.836853,507.097443,1696.227661,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,151160,155984,155567,153606 -6.906569,-0.031687,0.020963,-0.921301,-0.07056,-0.200239,0.005624,0,0.017936,0.041862,0.165531,0.196339,0.282214,671.233643,489.791321,2822.821045,0,0,-0.186409,0.120623,0.237799,-0.123557,-0.147595,-0.154476,0.089533,0.334481,0,150096,157084,156721,152418 -6.91157,-0.027049,0.025113,-0.925207,-0.05034,-0.21301,0.005624,0,0.009401,0.037501,0.163093,0.200452,0.176709,690.194458,460.232819,1746.067017,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151183,156056,155596,153484 -6.916571,-0.059275,0.020963,-0.919836,-0.040762,-0.194918,0.005624,0,0.009401,0.037501,0.163093,0.200452,0.176709,656.993713,442.655975,1746.067017,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,150996,155802,155373,153195 -6.921572,-0.043406,0.017301,-0.931311,-0.016285,-0.190661,0.001367,0,0.009401,0.037501,0.163093,0.200452,0.176709,649.181824,397.737335,1789.512207,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151005,155882,155380,153099 -6.926573,-0.036326,0.028775,-0.930334,-0.004578,-0.183212,0.000303,0,0.009401,0.037501,0.163093,0.200452,0.176709,635.510925,376.254517,1800.373413,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151029,155901,155383,153053 -6.931574,-0.023631,0.009488,-0.939123,0.030541,-0.175762,0.002431,0,0.009401,0.037501,0.163093,0.200452,0.176709,621.840027,311.806061,1778.650879,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151129,155930,155310,152996 -6.936575,-0.020945,0.028775,-0.9401,0.031606,-0.18534,-0.000762,0,0.009401,0.037501,0.163093,0.200452,0.176709,639.416931,309.853058,1811.234741,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151293,156194,155535,153192 -6.941576,-0.053416,-0.006625,-0.941076,0.07311,-0.158735,-0.001826,0,0.022522,0.047093,0.173849,0.202117,0.256373,610.332092,236.743118,2635.12793,0,0,-0.186108,0.12548,0.225344,-0.124075,-0.151327,-0.155025,0.089533,0.334481,0,150571,157062,156315,152265 -6.946577,-0.041941,0.013639,-0.945959,0.055019,-0.168313,0.000303,0,0.017676,0.044686,0.170953,0.197885,0.219845,622.593994,262.177338,2240.607178,0,0,-0.185706,0.127329,0.220928,-0.124114,-0.153277,-0.153199,0.089533,0.334481,0,150928,156655,155934,152698 -6.951578,-0.048533,-0.010287,-0.932531,0.10078,-0.141707,-0.008211,0,0.017349,0.045638,0.171588,0.197305,0.195062,574.934082,177.13472,2074.563721,0,0,-0.184913,0.129029,0.216505,-0.124139,-0.154239,-0.151667,0.089533,0.334481,0,151227,156526,155730,152731 -6.956579,-0.019725,0.015592,-0.940588,0.082688,-0.13745,-0.006083,0,0.017349,0.045638,0.171588,0.197305,0.195062,567.122131,210.335464,2052.841309,0,0,-0.184913,0.129029,0.216505,-0.124139,-0.154239,-0.151667,0.089533,0.334481,0,151223,156463,155750,152778 -6.96158,-0.02241,0.009488,-0.93009,0.112487,-0.131065,-0.011404,0,0.018582,0.047641,0.176735,0.199822,0.17726,564.85083,160.270859,1925.462402,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151410,156391,155581,152860 -6.966581,-0.025096,-0.004428,-0.938146,0.101845,-0.123615,-0.008211,0,0.018582,0.047641,0.176735,0.199822,0.17726,551.179932,179.800705,1892.87854,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151437,156325,155582,152899 -6.971582,-0.051951,0.012418,-0.928869,0.106101,-0.108716,-0.008211,0,0.018582,0.047641,0.176735,0.199822,0.17726,523.838196,171.98877,1892.87854,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151472,156305,155602,152863 -6.976583,-0.047801,-0.01932,-0.929357,0.123129,-0.085303,-0.01034,0,0.018582,0.047641,0.176735,0.199822,0.17726,480.872528,140.741028,1914.601074,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151524,156315,155635,152768 -6.981585,-0.04243,0.017545,-0.927648,0.099716,-0.073597,-0.009276,0,0.018582,0.047641,0.176735,0.199822,0.17726,459.389709,183.706665,1903.739868,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151622,156348,155797,152908 -6.986586,-0.027537,-0.008334,-0.929846,0.139092,-0.053376,-0.013532,0,0.018582,0.047641,0.176735,0.199822,0.17726,422.28302,111.446259,1947.184937,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151688,156427,155805,152755 -6.991587,-0.026316,0.022916,-0.936926,0.103973,-0.049119,-0.007147,0,0.018582,0.047641,0.176735,0.199822,0.17726,414.471069,175.89473,1882.017334,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151696,156289,155812,152877 -6.996588,-0.021922,0.006559,-0.931799,0.143349,-0.03422,-0.013532,0,0.018582,0.047641,0.176735,0.199822,0.17726,387.129303,103.634315,1947.184937,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151731,156399,155832,152712 -7.001589,-0.034129,0.000699,-0.926184,0.116744,-0.015064,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,361.496948,153.802368,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151377,156856,156441,152408 -7.00659,-0.043406,0.004605,-0.932287,0.142285,-0.012936,-0.013532,0,0.023289,0.054334,0.181924,0.200554,0.223726,357.590973,106.930756,2421.416016,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151385,156943,156441,152314 -7.011591,-0.051463,-0.008822,-0.937414,0.130579,0.015798,-0.011404,0,0.023289,0.054334,0.181924,0.200554,0.223726,304.860413,128.413589,2399.693359,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151438,156847,156494,152304 -7.016592,-0.042918,-0.002475,-0.942053,0.139092,0.010477,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,314.625336,112.789703,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151465,156850,156447,152320 -7.021593,-0.041453,-0.012484,-0.936682,0.138028,0.039211,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,261.894775,114.742691,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151516,156796,156501,152269 -7.026594,-0.030467,-0.007602,-0.948645,0.132707,0.026441,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,285.330597,124.507614,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151382,156708,156387,152201 -7.031595,-0.028514,-0.01102,-0.946203,0.139092,0.042404,-0.014597,0,0.023289,0.054334,0.181924,0.200554,0.223726,256.035828,112.789703,2432.277344,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151368,156745,156459,152106 -7.036596,-0.034861,-0.011996,-0.951574,0.124193,0.040276,-0.008211,0,0.023289,0.054334,0.181924,0.200554,0.223726,259.941803,140.131485,2367.109619,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151402,156656,156417,152202 -7.041597,-0.028514,-0.00101,-0.962316,0.115679,0.028569,-0.009276,0,0.028358,0.062464,0.186246,0.202401,0.31936,289.356995,159.144669,3353.991211,0,0,-0.187995,0.144686,0.17967,-0.12193,-0.157888,-0.139938,0.089533,0.334481,0,150367,157654,157393,151264 -7.046598,-0.041941,-0.009799,-0.95133,0.10078,0.049854,-0.005019,0,0.023663,0.056983,0.181776,0.196189,0.239166,242.093414,175.087311,2492.101807,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151262,156731,156597,152097 -7.0516,-0.033396,0.010221,-0.959875,0.081624,0.027505,-0.005019,0,0.023663,0.056983,0.181776,0.196189,0.239166,283.106079,210.241013,2492.101807,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151186,156736,156591,152173 -7.056601,-0.04243,0.001187,-0.954748,0.079496,0.05411,-0.00289,0,0.023663,0.056983,0.181776,0.196189,0.239166,234.281479,214.146988,2470.379395,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151253,156662,156622,152150 -7.061602,-0.02241,0.009732,-0.962561,0.06034,0.029633,-0.001826,0,0.023663,0.056983,0.181776,0.196189,0.239166,279.200104,249.30069,2459.518066,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151183,156661,156601,152240 -7.066603,-0.03657,0.011197,-0.955725,0.055019,0.053046,-0.000762,0,0.023663,0.056983,0.181776,0.196189,0.239166,236.234467,259.065613,2448.656738,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151228,156597,156643,152218 -7.071604,-0.027781,0.004361,-0.95841,0.041184,0.027505,0.002431,0,0.023663,0.056983,0.181776,0.196189,0.239166,283.106079,284.454407,2416.072998,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151298,156696,156699,152433 -7.076605,-0.042674,0.01315,-0.948889,0.033734,0.042404,-0.000762,0,0.029308,0.067461,0.18471,0.206612,0.305971,261.148407,317.252167,3130.456787,0,0,-0.188165,0.152253,0.161987,-0.119807,-0.155402,-0.139151,0.089533,0.334481,0,150573,157356,157468,151729 -7.081606,-0.038279,-0.000766,-0.949133,0.033734,0.032826,0.003495,0,0.025529,0.06212,0.180739,0.20275,0.25357,271.437866,310.165466,2552.217529,0,0,-0.187791,0.154838,0.155801,-0.119053,-0.155209,-0.14063,0.089533,0.334481,0,151148,156795,156872,152311 -7.086607,-0.037791,0.017301,-0.944494,0.010321,0.022184,0.001367,0,0.031373,0.067916,0.182624,0.202434,0.288092,294.427826,352.551117,2926.263428,0,0,-0.188514,0.160656,0.142871,-0.117538,-0.151251,-0.134519,0.089533,0.334481,0,150708,157150,157266,152002 -7.091608,-0.034861,-0.001254,-0.948156,0.028413,0.030697,0.003495,0,0.02954,0.068626,0.180453,0.203518,0.281601,274.820435,321.339905,2838.296631,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150731,156957,157050,151923 -7.096609,-0.034129,0.008512,-0.948889,0.000743,0.017927,0.005624,0,0.02954,0.068626,0.180453,0.203518,0.281601,298.256256,372.117493,2816.574219,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150679,156908,157056,152019 -7.10161,-0.025584,-0.008334,-0.950109,0.026285,0.016863,0.007752,0,0.02954,0.068626,0.180453,0.203518,0.281601,300.209229,325.24588,2794.851562,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150745,156935,156985,151996 -7.106611,-0.035105,-0.000766,-0.954748,-0.00245,0.008349,0.013073,0,0.02954,0.068626,0.180453,0.203518,0.281601,315.833099,377.97644,2740.545166,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150731,156844,156968,152119 -7.111612,-0.039256,-0.008578,-0.953527,0.019899,0.004092,0.008816,0,0.02954,0.068626,0.180453,0.203518,0.281601,323.64505,336.963776,2783.990234,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,151094,157309,157336,152415 -7.116613,-0.039744,-0.000766,-0.961828,-0.003514,-0.003358,0.014137,0,0.02954,0.068626,0.180453,0.203518,0.281601,337.315918,379.929413,2729.683838,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,151092,157226,157311,152526 -7.121614,-0.038035,0.000455,-0.963537,0.000743,-0.011872,0.010945,0,0.02954,0.068626,0.180453,0.203518,0.281601,352.939789,372.117493,2762.267822,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,151051,157282,157320,152501 -7.126616,-0.03242,-0.000277,-0.968176,-0.001385,-0.015064,0.016266,0,0.031957,0.07115,0.187385,0.208202,0.24282,371.519928,384.618591,2312.166504,0,0,-0.187264,0.172737,0.115627,-0.113294,-0.155429,-0.137052,0.089533,0.334481,0,151470,156838,156864,152982 -7.131617,-0.047312,0.010465,-0.964025,-0.009899,-0.022514,0.01733,0,0.03429,0.073114,0.185804,0.206848,0.250766,382.288483,397.757111,2382.395264,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,151376,156905,156936,152936 -7.136618,-0.035594,0.003141,-0.971594,0.002872,-0.031028,0.016266,0,0.03429,0.073114,0.185804,0.206848,0.250766,397.912354,374.321289,2393.256592,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152132,157714,157667,153676 -7.141619,-0.048289,0.012174,-0.972326,-0.016285,-0.025706,0.018394,0,0.03429,0.073114,0.185804,0.206848,0.250766,388.14743,409.475006,2371.533936,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152128,157648,157690,153724 -7.14662,-0.02241,0.013883,-0.984777,0.003936,-0.037413,0.013073,0,0.03429,0.073114,0.185804,0.206848,0.250766,409.630249,372.368317,2425.840332,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152090,157761,157686,153654 -7.151621,-0.047557,0.014859,-0.980383,-0.017349,-0.03422,0.015202,0,0.03429,0.073114,0.185804,0.206848,0.250766,403.771301,411.427979,2404.11792,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152078,157694,157709,153709 -7.156622,-0.033641,0.01608,-0.992102,-0.007771,-0.048055,0.014137,0,0.03429,0.073114,0.185804,0.206848,0.250766,429.160095,393.851135,2414.979004,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152357,158045,157974,154003 -7.161623,-0.052684,0.014615,-0.985021,-0.021606,-0.036349,0.01733,0,0.034556,0.076417,0.192396,0.217697,0.224836,419.774536,439.148804,2117.760986,0,0,-0.186494,0.179379,0.101209,-0.111117,-0.15784,-0.14128,0.089533,0.334481,0,152618,157693,157732,154336 -7.166624,-0.04951,0.005338,-0.987219,-0.013092,-0.052312,0.01733,0,0.036654,0.077008,0.188155,0.20997,0.247249,441.286743,409.344971,2346.510742,0,0,-0.186568,0.186413,0.086255,-0.108851,-0.151501,-0.132962,0.089533,0.334481,0,152397,157973,157909,154099 -7.171625,-0.045848,0.010953,-0.980627,-0.018413,-0.039541,0.018394,0,0.037087,0.079101,0.192875,0.218182,0.212564,426.512482,434.179932,1981.658447,0,0,-0.185859,0.190014,0.078614,-0.107459,-0.155788,-0.139081,0.089533,0.334481,0,152752,157568,157584,154474 -7.176626,-0.041941,-0.007113,-0.983312,-0.009899,-0.054441,0.020523,0,0.037087,0.079101,0.192875,0.218182,0.212564,453.854248,418.556061,1959.935913,0,0,-0.185859,0.190014,0.078614,-0.107459,-0.155788,-0.139081,0.089533,0.334481,0,152762,157590,157519,154507 -7.181627,-0.024852,0.016812,-0.984289,-0.010963,-0.045927,0.016266,0,0.037447,0.083214,0.194248,0.222838,0.224946,440.749146,429.053314,2129.744873,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152596,157737,157714,154336 -7.186628,-0.03657,-0.003451,-0.986242,0.000743,-0.06189,0.018394,0,0.037447,0.083214,0.194248,0.222838,0.224946,470.043915,407.570496,2108.022217,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152610,157766,157641,154365 -7.191629,-0.042674,0.008756,-0.987951,-0.008835,-0.057633,0.023715,0,0.037447,0.083214,0.194248,0.222838,0.224946,462.231964,425.147369,2053.71582,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152654,157686,157612,154429 -7.19663,-0.061961,-0.011264,-0.983801,0.010321,-0.06189,0.02478,0,0.037447,0.083214,0.194248,0.222838,0.224946,470.043915,389.993652,2042.854614,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152693,157718,157558,154413 -7.201632,-0.053904,0.004605,-0.986975,0.006064,-0.049119,0.030101,0,0.037447,0.083214,0.194248,0.222838,0.224946,446.608093,397.805573,1988.548218,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152744,157614,157516,154432 -7.206633,-0.033641,0.007047,-0.982336,0.027349,-0.056569,0.027972,0,0.037447,0.083214,0.194248,0.222838,0.224946,460.278992,358.745911,2010.270752,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152747,157688,157485,154385 -7.211634,-0.02827,0.01315,-0.987463,0.03267,-0.053376,0.030101,0,0.037447,0.083214,0.194248,0.222838,0.224946,454.420044,348.980988,1988.548218,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152785,157670,157460,154391 -7.216635,-0.029246,0.03024,-0.982336,0.048633,-0.053376,0.030101,0,0.040285,0.083338,0.195573,0.222346,0.259162,456.853088,318.784637,2337.756592,0,0,-0.186231,0.197503,0.062519,-0.105039,-0.155289,-0.139008,0.089533,0.334481,0,152463,158052,157776,154014 -7.221636,-0.04365,0.018033,-0.988928,0.05289,-0.057633,0.031165,0,0.041178,0.086471,0.19879,0.216311,0.263751,470.567291,299.89798,2373.727539,0,0,-0.187107,0.209463,0.037533,-0.101701,-0.157612,-0.12984,0.089533,0.334481,0,152994,158683,158342,154535 -7.226637,-0.054148,0.028043,-0.983557,0.057147,-0.048055,0.031165,0,0.041178,0.086471,0.19879,0.216311,0.263751,452.990448,292.086029,2373.727539,0,0,-0.187107,0.209463,0.037533,-0.101701,-0.157612,-0.12984,0.089533,0.334481,0,153020,158673,158351,154510 -7.231638,-0.062937,0.018521,-0.977941,0.079496,-0.052312,0.032229,0,0.044573,0.089617,0.204107,0.222253,0.270843,470.560303,261.97757,2435.246826,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,152971,158782,158365,154436 -7.236639,-0.058299,0.025113,-0.988439,0.078432,-0.036349,0.041807,0,0.044573,0.089617,0.204107,0.222253,0.270843,441.265533,263.930542,2337.495361,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153096,158653,158299,154506 -7.24164,-0.033641,0.017545,-0.996008,0.109294,-0.055505,0.040743,0,0.044573,0.089617,0.204107,0.222253,0.270843,476.41925,207.294022,2348.356689,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153106,158756,158218,154474 -7.246641,-0.054393,0.013883,-0.994787,0.114615,-0.036349,0.042872,0,0.044573,0.089617,0.204107,0.222253,0.270843,441.265533,197.529099,2326.634033,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153876,159412,158924,155154 -7.251642,-0.039012,0.025113,-0.999914,0.141221,-0.064019,0.042872,0,0.044573,0.089617,0.204107,0.222253,0.270843,492.043121,148.704498,2326.634033,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153874,159511,158825,155156 -7.256643,-0.061961,0.001187,-0.998693,0.151863,-0.03422,0.045,0,0.044573,0.089617,0.204107,0.222253,0.270843,437.359558,129.174667,2304.911377,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153970,159455,158838,155103 -7.261644,-0.050486,0.010709,-1.015783,0.169955,-0.051248,0.045,0,0.044573,0.089617,0.204107,0.222253,0.270843,468.6073,95.973938,2304.911377,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153972,159519,158774,155101 -7.266645,-0.075877,0.004117,-1.007971,0.184854,-0.025706,0.046064,0,0.044184,0.089198,0.204167,0.217466,0.228434,421.844971,59.846752,1861.225464,0,0,-0.186249,0.226648,0.002861,-0.096305,-0.159982,-0.128268,0.089533,0.334481,0,155376,159942,159218,156339 -7.271646,-0.058787,0.002164,-1.015295,0.210396,-0.02145,0.047128,0,0.04702,0.091081,0.207762,0.216684,0.197385,420.631866,11.539858,1533.486694,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155753,159661,158843,156617 -7.276648,-0.060984,0.008756,-1.015295,0.221038,-0.000165,0.047128,0,0.04702,0.091081,0.207762,0.216684,0.197385,381.572205,-7.989988,1533.486694,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155811,159642,158862,156559 -7.281649,-0.047801,-0.007113,-1.027014,0.248708,0.008349,0.05245,0,0.04702,0.091081,0.207762,0.216684,0.197385,365.948334,-58.767559,1479.18042,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155932,159622,158773,156547 -7.28665,-0.042186,0.022428,-1.019934,0.245515,0.017927,0.051385,0,0.04702,0.091081,0.207762,0.216684,0.197385,348.37146,-52.908604,1490.041626,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155933,159610,158807,156524 -7.291651,-0.05952,-0.006137,-1.009436,0.278506,0.039211,0.053514,0,0.04702,0.091081,0.207762,0.216684,0.197385,309.311798,-113.451096,1468.319092,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,156608,160164,159318,157000 -7.296652,-0.046824,0.027799,-1.009924,0.255093,0.029633,0.053514,0,0.04702,0.091081,0.207762,0.216684,0.197385,326.888641,-70.485435,1468.319092,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,156548,160138,159343,157061 -7.301653,-0.085398,-0.003207,-1.012609,0.290212,0.058367,0.056706,0,0.016103,0.031311,0.173389,0.14631,0.1862,211.079056,-264.078735,1321.584229,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157004,160069,159119,156898 -7.306654,-0.068064,0.025846,-1.021643,0.272121,0.056239,0.058835,0,0.016103,0.031311,0.173389,0.14631,0.1862,214.985031,-230.878036,1299.861694,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,156989,160018,159126,156957 -7.311655,-0.079051,0.011441,-1.014562,0.298726,0.071138,0.058835,0,0.016103,0.031311,0.173389,0.14631,0.1862,187.64325,-279.702637,1299.861694,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157348,160323,159388,157164 -7.316656,-0.05073,0.020963,-1.020178,0.293405,0.082845,0.062028,0,0.016103,0.031311,0.173389,0.14631,0.1862,166.160431,-269.937714,1267.277954,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157392,160259,159387,157184 -7.321657,-0.049266,0.031217,-1.01676,0.298726,0.082845,0.062028,0,0.016103,0.031311,0.173389,0.14631,0.1862,166.160431,-279.702637,1267.277954,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157402,160269,159377,157175 -7.326658,-0.045359,0.017545,-1.037756,0.296598,0.092423,0.066285,0,0.016103,0.031311,0.173389,0.14631,0.1862,148.583572,-275.796661,1223.832764,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157459,160204,159355,157204 -7.331659,-0.043895,0.043668,-1.029699,0.27957,0.086037,0.067349,0,0.016103,0.031311,0.173389,0.14631,0.1862,160.301483,-244.54895,1212.971558,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157530,160276,159467,157361 -7.33666,-0.062693,0.012662,-1.026525,0.294469,0.103065,0.071606,0,0.061309,0.119574,0.216748,0.231977,0.182303,208.623077,-114.680603,1129.75647,0,0,-0.183109,0.250003,-0.042463,-0.090178,-0.15544,-0.112404,0.089533,0.334481,0,157435,160112,159465,157623 -7.341661,-0.064402,0.042203,-1.043859,0.247643,0.08923,0.077991,0,0.045345,0.101756,0.211988,0.181532,0.458522,225.275558,-121.323242,3883.623779,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154671,162889,162196,154879 -7.346663,-0.08076,0.007047,-1.047033,0.276378,0.106257,0.073734,0,0.045345,0.101756,0.211988,0.181532,0.458522,194.027817,-174.053802,3927.068848,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154711,162954,162217,154751 -7.351664,-0.075145,0.0361,-1.049963,0.225295,0.108386,0.084376,0,0.045345,0.101756,0.211988,0.181532,0.458522,190.121841,-80.310562,3818.456055,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154730,162747,162207,154950 -7.356665,-0.066355,0.016324,-1.051916,0.258286,0.10945,0.082248,0,0.045345,0.101756,0.211988,0.181532,0.458522,188.168869,-140.853088,3840.178711,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154870,162927,162269,154965 -7.361666,-0.068309,0.012174,-1.069006,0.213588,0.121157,0.090762,0,0.045345,0.101756,0.211988,0.181532,0.458522,166.686035,-58.827763,3753.288574,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154896,162736,162285,155112 -7.366667,-0.044627,0.016812,-1.0734,0.228487,0.104129,0.089697,0,0.045345,0.101756,0.211988,0.181532,0.458522,197.933792,-86.169518,3764.149658,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154882,162806,162238,155105 -7.371668,-0.063182,0.000455,-1.080725,0.200818,0.122221,0.10034,0,0.057154,0.100306,0.220658,0.172981,0.286587,180.644913,-51.08297,1900.801758,0,0,-0.190796,0.28022,-0.102801,-0.084849,-0.163504,-0.072676,0.089533,0.334481,0,156727,160890,160427,156986 -7.376669,-0.043406,0.022672,-1.084143,0.192304,0.092423,0.103532,0,0.057154,0.100306,0.220658,0.172981,0.286587,235.328476,-35.459091,1868.218018,0,0,-0.190796,0.28022,-0.102801,-0.084849,-0.163504,-0.072676,0.089533,0.334481,0,156693,160901,160359,157093 -7.38167,-0.072703,-0.005648,-1.085852,0.172083,0.112643,0.112046,0,0.057154,0.100306,0.220658,0.172981,0.286587,198.221771,1.647587,1781.327881,0,0,-0.190796,0.28022,-0.102801,-0.084849,-0.163504,-0.072676,0.089533,0.334481,0,156780,160739,160346,157180 -7.386671,-0.055125,0.023893,-1.1005,0.144414,0.08178,0.117367,0,0.0546,0.10806,0.217509,0.176964,0.318973,249.078918,59.733551,2057.544922,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156395,161008,160630,157013 -7.391672,-0.086375,-0.006381,-1.088781,0.143349,0.120092,0.126945,0,0.0546,0.10806,0.217509,0.176964,0.318973,178.7715,61.686535,1959.793457,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156561,160838,160604,157042 -7.396673,-0.07368,0.016812,-1.110266,0.103973,0.088166,0.136523,0,0.0546,0.10806,0.217509,0.176964,0.318973,237.361023,133.946945,1862.041992,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156528,160727,160520,157271 -7.401674,-0.086375,0.007779,-1.106115,0.105037,0.128606,0.138652,0,0.0546,0.10806,0.217509,0.176964,0.318973,163.147644,131.993973,1840.319458,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156624,160631,160569,157214 -7.406675,-0.078074,0.002164,-1.106115,0.075239,0.104129,0.150358,0,0.0546,0.10806,0.217509,0.176964,0.318973,208.066269,186.677505,1720.845581,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156644,160502,160459,157433 -7.411676,-0.070994,0.017545,-1.099523,0.059276,0.126478,0.150358,0,0.0546,0.10806,0.217509,0.176964,0.318973,167.053619,215.972275,1720.845581,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156656,160431,160529,157422 -7.416677,-0.065623,-0.011264,-1.102209,0.045441,0.112643,0.156744,0,0.059719,0.102206,0.222444,0.170981,0.239923,201.498535,230.381775,848.909546,0,0,-0.189346,0.291269,-0.123155,-0.083388,-0.162725,-0.068775,0.089533,0.334481,0,157479,159580,159637,158342 -7.421679,-0.055125,0.026822,-1.105627,0.011385,0.112643,0.157808,0,0.059288,0.107616,0.217677,0.177598,0.187801,192.750763,305.02002,306.099945,0,0,-0.185459,0.308589,-0.15405,-0.08198,-0.15839,-0.069982,0.089533,0.334481,0,157684,158681,158906,158679 -7.42668,-0.061717,-0.007602,-1.104406,0.005,0.103065,0.163129,0,0.059288,0.107616,0.217677,0.177598,0.187801,210.327606,316.737915,251.793549,0,0,-0.185459,0.308589,-0.15405,-0.08198,-0.15839,-0.069982,0.089533,0.334481,0,157709,158633,158846,158763 -7.431681,-0.053172,0.027066,-1.099035,-0.045019,0.093487,0.167386,0,0.066857,0.105287,0.224705,0.17841,0.115969,240.800568,410.018951,-524.75415,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158361,157794,158132,159663 -7.436682,-0.077342,-0.001498,-1.095129,-0.052468,0.099872,0.170579,0,0.066857,0.105287,0.224705,0.17841,0.115969,229.082657,423.689819,-557.338013,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158392,157736,158125,159698 -7.441683,-0.059031,0.029752,-1.101965,-0.105679,0.083909,0.176964,0,0.066857,0.105287,0.224705,0.17841,0.115969,258.377411,521.338989,-622.505493,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158100,157372,157898,159660 -7.446684,-0.088572,0.007535,-1.090002,-0.108872,0.104129,0.176964,0,0.066857,0.105287,0.224705,0.17841,0.115969,221.270737,527.197937,-622.505493,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158132,157329,157941,159628 -7.451685,-0.068553,0.026334,-1.095861,-0.149313,0.095615,0.183349,0,0.066857,0.105287,0.224705,0.17841,0.115969,236.894592,601.411377,-687.673157,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158107,157205,157934,159783 -7.456686,-0.081736,0.022184,-1.086584,-0.155698,0.10945,0.184414,0,0.066857,0.105287,0.224705,0.17841,0.115969,211.505814,613.129211,-698.534485,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158131,157157,157961,159781 -7.461687,-0.067332,0.027799,-1.09635,-0.184432,0.115836,0.189735,0,0.063008,0.113245,0.21899,0.192147,0.099716,189.3004,691.067932,-918.709106,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158296,156837,157841,160057 -7.466688,-0.052928,0.033658,-1.084631,-0.20146,0.115836,0.18867,0,0.063008,0.113245,0.21899,0.192147,0.099716,189.3004,722.315674,-907.847839,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158256,156819,157885,160079 -7.471689,-0.057078,0.025113,-1.088537,-0.208909,0.12967,0.192927,0,0.063008,0.113245,0.21899,0.192147,0.099716,163.911621,735.986572,-951.292969,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158311,156736,157880,160111 -7.47669,-0.045359,0.047818,-1.085363,-0.237643,0.117964,0.193992,0,0.063008,0.113245,0.21899,0.192147,0.099716,185.39444,788.717102,-962.154236,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158248,156694,157901,160196 -7.481691,-0.062449,0.024625,-1.086828,-0.231258,0.121157,0.192927,0,0.063008,0.113245,0.21899,0.192147,0.099716,179.535477,776.999207,-951.292969,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158254,156711,157906,160167 -7.486692,-0.052439,0.05441,-1.077062,-0.263185,0.114771,0.189735,0,0.063008,0.113245,0.21899,0.192147,0.099716,191.253387,835.588745,-918.709106,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158225,156770,158059,160279 -7.491693,-0.064402,0.024869,-1.069494,-0.237643,0.115836,0.18867,0,0.063008,0.113245,0.21899,0.192147,0.099716,189.3004,788.717102,-907.847839,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158263,156826,158025,160219 -7.496695,-0.072215,0.037809,-1.077307,-0.274891,0.112643,0.192927,0,0.065107,0.116785,0.221244,0.196737,0.127133,199.297287,865.494873,-671.486023,0,0,-0.1794,0.339828,-0.207872,-0.081775,-0.156137,-0.079952,0.089533,0.334481,0,157940,156996,158328,160070 -7.501696,-0.07783,0.015592,-1.073889,-0.242965,0.114771,0.189735,0,0.073504,0.110478,0.223881,0.206801,-0.068366,200.228775,825.37384,-2634.121338,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159942,155074,156325,161993 -7.506697,-0.081492,0.017057,-1.07633,-0.279148,0.119028,0.195056,0,0.073504,0.110478,0.223881,0.206801,-0.068366,192.41684,891.77533,-2688.427734,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159938,154946,156344,162106 -7.511698,-0.080271,0.002896,-1.068029,-0.244029,0.119028,0.18867,0,0.073504,0.110478,0.223881,0.206801,-0.068366,192.41684,827.326843,-2623.26001,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159935,155073,156343,161975 -7.516699,-0.083201,0.00192,-1.074865,-0.266378,0.128606,0.192927,0,0.073504,0.110478,0.223881,0.206801,-0.068366,174.839981,868.339539,-2666.705322,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159955,154971,156358,162041 -7.5217,-0.068309,0.000699,-1.066564,-0.242965,0.121157,0.186542,0,0.073504,0.110478,0.223881,0.206801,-0.068366,188.510864,825.37384,-2601.537598,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159919,155093,156367,161947 -7.526701,-0.074656,-0.004184,-1.059729,-0.245093,0.139248,0.186542,0,0.073504,0.110478,0.223881,0.206801,-0.068366,155.310135,829.279846,-2601.537598,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159948,155056,156404,161918 -7.531702,-0.057078,0.007779,-1.060949,-0.237643,0.1169,0.182285,0,0.068505,0.122699,0.216012,0.224166,-0.043547,181.882645,847.476746,-2304.795654,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159754,155508,156839,161813 -7.536703,-0.067332,0.00192,-1.05924,-0.225937,0.136056,0.182285,0,0.068505,0.122699,0.216012,0.224166,-0.043547,146.728943,825.993896,-2304.795654,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159811,155494,156853,161756 -7.541704,-0.052439,0.016324,-1.066564,-0.233387,0.104129,0.181221,0,0.068505,0.122699,0.216012,0.224166,-0.043547,205.318466,839.664795,-2293.934326,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159727,155550,156819,161817 -7.546705,-0.064891,0.012906,-1.051672,-0.215295,0.125414,0.178028,0,0.068505,0.122699,0.216012,0.224166,-0.043547,166.258789,806.46405,-2261.350586,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159767,155577,156857,161713 -7.551706,-0.056834,0.029508,-1.05802,-0.22913,0.096679,0.1759,0,0.068505,0.122699,0.216012,0.224166,-0.043547,218.989334,831.852844,-2239.628174,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159955,155914,157140,162057 -7.556707,-0.068309,0.026822,-1.051672,-0.204652,0.115836,0.174836,0,0.068505,0.122699,0.216012,0.224166,-0.043547,183.835632,786.934204,-2228.766846,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,160024,155935,157141,161966 -7.561708,-0.065379,0.036832,-1.063146,-0.219552,0.092423,0.172707,0,0.068505,0.122699,0.216012,0.224166,-0.043547,226.801285,814.276001,-2207.044189,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159932,155972,157147,162015 -7.56671,-0.067576,0.039029,-1.056066,-0.185496,0.115836,0.166322,0,0.077247,0.117799,0.224824,0.223397,-0.107857,200.006302,750.36908,-2798.217773,0,0,-0.167757,0.388222,-0.286705,-0.084367,-0.147577,-0.105598,0.089533,0.334481,0,160614,155418,156519,162515 -7.571711,-0.065379,0.034391,-1.067297,-0.197203,0.095615,0.164193,0,0.074233,0.124761,0.217603,0.235151,-0.138711,223.861664,793.422363,-3091.38208,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160841,155106,156245,162875 -7.576712,-0.067576,0.041959,-1.063391,-0.161019,0.10945,0.154615,0,0.074233,0.124761,0.217603,0.235151,-0.138711,198.47287,727.020874,-2993.630615,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160740,155149,156206,162591 -7.581713,-0.070262,0.028531,-1.065344,-0.169533,0.098808,0.156744,0,0.074233,0.124761,0.217603,0.235151,-0.138711,218.002701,742.644775,-3015.353271,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160726,155132,156181,162648 -7.586714,-0.060252,0.033658,-1.057775,-0.131221,0.107322,0.146101,0,0.074233,0.124761,0.217603,0.235151,-0.138711,202.378845,672.337341,-2906.740479,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160704,155295,156235,162453 -7.591715,-0.068797,0.024869,-1.058508,-0.137606,0.105193,0.146101,0,0.074233,0.124761,0.217603,0.235151,-0.138711,206.284805,684.055298,-2906.740479,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160688,155287,156243,162469 -7.596716,-0.056102,0.02902,-1.054357,-0.104615,0.100936,0.136523,0,0.074233,0.124761,0.217603,0.235151,-0.138711,214.096741,623.512756,-2808.989014,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160126,154936,155755,161801 -7.601717,-0.071727,0.018766,-1.045568,-0.107808,0.110514,0.136523,0,0.074673,0.128206,0.217683,0.23993,-0.124607,196.666977,638.142029,-2665.043457,0,0,-0.163702,0.424531,-0.347049,-0.088231,-0.14301,-0.111725,0.089533,0.334481,0,159985,155048,155931,161654 -7.606718,-0.058055,0.025113,-1.050451,-0.085459,0.096679,0.129074,0,0.089477,0.117668,0.228576,0.232425,-0.267071,242.046722,583.356873,-4042.97876,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,161372,153770,154453,163023 -7.611719,-0.065379,0.013639,-1.039221,-0.082267,0.1169,0.125881,0,0.089477,0.117668,0.228576,0.232425,-0.267071,204.940033,577.497925,-4010.394775,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,161382,153772,154517,162947 -7.61672,-0.044139,0.023648,-1.04215,-0.069496,0.094551,0.115239,0,0.089477,0.117668,0.228576,0.232425,-0.267071,245.952682,554.062134,-3901.781982,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,161256,153945,154561,162856 -7.621721,-0.053416,0.013639,-1.030187,-0.058854,0.111579,0.11311,0,0.089477,0.117668,0.228576,0.232425,-0.267071,214.704956,534.532288,-3880.05957,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,157849,150519,151158,159348 -7.626722,-0.038523,0.025357,-1.039221,-0.055661,0.08178,0.109918,0,0.089477,0.117668,0.228576,0.232425,-0.267071,269.388489,528.67334,-3847.47583,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,157768,150612,151130,159364 -7.631723,-0.057078,0.017789,-1.025549,-0.037569,0.092423,0.105661,0,0.089477,0.117668,0.228576,0.232425,-0.267071,249.858658,495.472626,-3804.030518,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,157777,150669,151160,159268 -7.636724,-0.048289,0.024869,-1.036047,-0.043954,0.06901,0.102468,0,0.067557,0.14036,0.205886,0.251562,-0.11955,251.184753,542.308655,-2265.871826,0,0,-0.162191,0.454155,-0.397713,-0.092197,-0.138329,-0.111202,0.089533,0.334481,0,156191,152162,152744,157778 -7.641726,-0.06367,0.019742,-1.020422,-0.018413,0.075395,0.096083,0,0.084861,0.129237,0.222493,0.238979,-0.173892,269.942993,472.345856,-2755.311035,0,0,-0.161425,0.461941,-0.410496,-0.093343,-0.137633,-0.109742,0.089533,0.334481,0,149223,144252,144657,150707 -7.646727,-0.059275,0.023893,-1.034338,-0.025863,0.06156,0.093954,0,0.084861,0.129237,0.222493,0.238979,-0.173892,295.331757,486.016724,-2733.588379,0,0,-0.161425,0.461941,-0.410496,-0.093343,-0.137633,-0.109742,0.089533,0.334481,0,149162,144285,144667,150724 -7.651728,-0.061473,0.024625,-1.015783,0.009257,0.063688,0.087569,0,0.083746,0.133366,0.217717,0.247795,-0.222316,282.661072,437.747009,-3162.621582,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,149652,143892,144202,151093 -7.656729,-0.05952,0.017545,-1.01798,-0.001385,0.059432,0.087569,0,0.083746,0.133366,0.217717,0.247795,-0.222316,290.473022,457.276825,-3162.621582,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,149624,143880,144214,151120 -7.66173,-0.055369,0.02316,-1.004553,0.036927,0.046661,0.080119,0,0.083746,0.133366,0.217717,0.247795,-0.222316,313.908813,386.969421,-3086.592529,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135792,130247,130393,137194 -7.666731,-0.069041,0.014371,-1.004064,0.030541,0.05411,0.082248,0,0.083746,0.133366,0.217717,0.247795,-0.222316,300.237946,398.687317,-3108.315186,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135816,130200,130397,137214 -7.671732,-0.058787,0.020963,-0.985266,0.063532,0.034954,0.077991,0,0.083746,0.133366,0.217717,0.247795,-0.222316,335.391632,338.144806,-3064.869873,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135798,130339,130344,137145 -7.676733,-0.060008,0.009,-0.978918,0.063532,0.04134,0.075863,0,0.083746,0.133366,0.217717,0.247795,-0.222316,323.673737,338.144806,-3043.147461,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135788,130349,130378,137111 -7.681734,-0.035105,0.023648,-0.960607,0.092266,0.023248,0.067349,0,0.074348,0.141323,0.205736,0.25058,-0.152841,334.887909,290.524475,-2247.20874,0,0,-0.16056,0.484971,-0.450223,-0.096557,-0.131388,-0.109257,0.089533,0.334481,0,135028,131204,131115,136279 -7.686735,-0.048289,0.022184,-0.944006,0.096523,0.015798,0.063092,0,0.086953,0.135274,0.215419,0.240675,-0.197439,366.328094,264.535248,-2658.928711,0,0,-0.159839,0.493077,-0.463455,-0.097463,-0.128466,-0.105401,0.089533,0.334481,0,116905,112319,112116,118166 -7.691736,-0.027293,0.029264,-0.929846,0.116744,-0.002294,0.057771,0,0.081129,0.14002,0.207606,0.244914,-0.198416,385.191986,235.207672,-2614.594238,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,116871,112412,112112,118111 -7.696737,-0.058055,0.013395,-0.905187,0.123129,-0.018257,0.055642,0,0.081129,0.14002,0.207606,0.244914,-0.198416,414.486725,223.489792,-2592.871582,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,116831,112475,112093,118107 -7.701738,-0.046336,0.023648,-0.902014,0.122065,-0.019321,0.05245,0,0.081129,0.14002,0.207606,0.244914,-0.198416,416.439728,225.442764,-2560.287842,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,116795,112507,112125,118079 -7.706739,-0.062205,0.016568,-0.866125,0.138028,-0.038477,0.050321,0,0.081129,0.14002,0.207606,0.244914,-0.198416,451.593414,196.147995,-2538.565186,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109472,105298,104787,110768 -7.71174,-0.06074,0.027311,-0.844641,0.131643,-0.026771,0.051385,0,0.081129,0.14002,0.207606,0.244914,-0.198416,430.110596,207.865906,-2549.426514,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109493,105254,104810,110769 -7.716742,-0.045115,0.022916,-0.829992,0.16357,-0.060826,0.046064,0,0.081129,0.14002,0.207606,0.244914,-0.198416,492.606079,149.276398,-2495.120117,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109435,105430,104743,110719 -7.721743,-0.035594,0.025602,-0.804846,0.16357,-0.050184,0.043936,0,0.081129,0.14002,0.207606,0.244914,-0.198416,473.076263,149.276398,-2473.397705,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109433,105432,104784,110677 -7.726744,-0.005564,0.0361,-0.800451,0.161441,-0.086367,0.03755,0,0.084299,0.1416,0.219547,0.242464,-0.207822,561.391052,148.686157,-2504.219971,0,0,-0.158378,0.525331,-0.517803,-0.101139,-0.135249,-0.100864,0.089533,0.334481,0,109376,105490,104665,110796 -7.731745,-0.04951,0.023404,-0.762609,0.166762,-0.104459,0.03755,0,0.054831,0.162636,0.187579,0.255708,-0.015594,535.926147,163.226196,-542.38208,0,0,-0.162234,0.531364,-0.533002,-0.101202,-0.132748,-0.093072,0.089533,0.334481,0,107433,107420,106674,108831 -7.736746,-0.059275,0.021695,-0.736975,0.167827,-0.108716,0.040743,0,0.054831,0.162636,0.187579,0.255708,-0.015594,543.738037,161.273209,-574.965881,0,0,-0.162234,0.531364,-0.533002,-0.101202,-0.132748,-0.093072,0.089533,0.334481,0,107459,107397,106632,108869 -7.741747,-0.054148,0.008512,-0.723059,0.190175,-0.131065,0.038615,0,0.117246,0.121577,0.247779,0.213784,-0.295053,695.225342,43.324322,-3405.343994,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110256,104836,103532,111733 -7.746748,-0.020213,0.034635,-0.686926,0.186983,-0.127872,0.035422,0,0.117246,0.121577,0.247779,0.213784,-0.295053,689.366394,49.183273,-3372.760254,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110224,104857,103577,111701 -7.751749,-0.007518,0.032682,-0.687902,0.18379,-0.167248,0.031165,0,0.117246,0.121577,0.247779,0.213784,-0.295053,761.62677,55.042202,-3329.315186,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110164,105029,103616,111797 -7.75675,-0.05073,0.020475,-0.654943,0.196561,-0.17257,0.035422,0,0.117246,0.121577,0.247779,0.213784,-0.295053,771.391724,31.606413,-3372.760254,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110221,105019,103539,111827 -7.761751,-0.04658,0.025846,-0.625646,0.200818,-0.169377,0.032229,0,0.117246,0.121577,0.247779,0.213784,-0.295053,765.532776,23.794476,-3340.17627,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110202,105053,103570,111781 -7.766752,-0.020701,0.018521,-0.640051,0.205074,-0.201304,0.031165,0,0.117246,0.121577,0.247779,0.213784,-0.295053,824.122253,15.982536,-3329.315186,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110141,105130,103514,111821 -7.771753,-0.031932,0.041959,-0.611486,0.197625,-0.203432,0.033294,0,0.070572,0.156536,0.21139,0.243836,-0.166261,761.249573,84.803123,-2036.616577,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108849,106298,104945,110541 -7.776754,-0.037791,0.021451,-0.588049,0.212524,-0.218331,0.033294,0,0.070572,0.156536,0.21139,0.243836,-0.166261,788.59137,57.461342,-2036.616577,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108849,106353,104891,110541 -7.781755,-0.022898,0.028775,-0.581457,0.214652,-0.23323,0.031165,0,0.070572,0.156536,0.21139,0.243836,-0.166261,815.933105,53.555374,-2014.893921,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108804,106406,104881,110543 -7.786757,-0.030711,0.040982,-0.560705,0.210396,-0.242809,0.033294,0,0.070572,0.156536,0.21139,0.243836,-0.166261,833.51001,61.367313,-2036.616577,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108800,106394,104850,110590 -7.791758,-0.035838,0.021695,-0.549475,0.21146,-0.266221,0.034358,0,0.070572,0.156536,0.21139,0.243836,-0.166261,876.475647,59.41433,-2047.477783,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108770,106428,104794,110642 -7.796759,-0.033885,0.037076,-0.538,0.213588,-0.270478,0.031165,0,0.070572,0.156536,0.21139,0.243836,-0.166261,884.287537,55.508358,-2014.893921,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108670,106408,104751,110549 -7.80176,-0.033885,0.048551,-0.514074,0.21146,-0.284313,0.03755,0,0.070572,0.156536,0.21139,0.243836,-0.166261,909.676331,59.41433,-2080.061523,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108705,106365,104664,110644 -7.806761,-0.036326,0.032437,-0.502844,0.209331,-0.303469,0.039679,0,0.08693,0.141877,0.22657,0.2211,-0.15903,972.686096,21.596989,-2027.983032,0,0,-0.160134,0.573169,-0.602537,-0.097799,-0.13964,-0.079223,0.089533,0.334481,0,108628,106518,104615,110617 -7.811762,-0.026561,0.041715,-0.497229,0.205074,-0.319433,0.035422,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1043.664551,34.786846,-2976.292236,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109492,105627,103609,111649 -7.816763,-0.041697,0.040006,-0.476965,0.207203,-0.326882,0.045,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1057.335449,30.880877,-3074.043701,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109583,105550,103497,111760 -7.821764,-0.03657,0.031461,-0.469885,0.205074,-0.340717,0.046064,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1082.724243,34.786846,-3084.905029,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109565,105561,103465,111800 -7.826765,-0.023387,0.03732,-0.465734,0.196561,-0.360938,0.045,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1119.830933,50.410721,-3074.043701,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109501,105593,103454,111842 -7.831766,-0.037059,0.041471,-0.441564,0.199753,-0.354552,0.053514,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1108.113037,44.551769,-3160.934082,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109606,105500,103373,111911 -7.836767,-0.034129,0.031217,-0.443273,0.190175,-0.379029,0.056706,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1153.031616,62.128628,-3193.517822,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109576,105495,103313,112006 -7.841768,-0.029734,0.032682,-0.432287,0.193368,-0.388607,0.056706,0,0.069722,0.158852,0.230424,0.223678,-0.12595,1135.998291,55.623474,-1864.159912,0,0,-0.159895,0.615028,-0.673571,-0.082945,-0.160702,-0.064827,0.089533,0.334481,0,108263,106807,104646,110646 -7.846769,-0.067088,0.069547,-0.429846,0.182726,-0.3918,0.06522,0,0.105465,0.136638,0.266858,0.197858,-0.230062,1208.717407,27.770313,-3013.595947,0,0,-0.158705,0.624321,-0.687302,-0.078415,-0.161393,-0.06122,0.089533,0.334481,0,109368,105758,103396,111841 -7.85177,-0.192088,0.188688,-0.683752,0.32746,-0.253451,0.071606,0,0.089104,0.146444,0.253375,0.202955,-0.229283,930.086731,-228.483124,-3070.804443,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,109960,105678,103361,111363 -7.856771,-0.230418,0.187955,-0.908117,0.521149,-0.027835,0.071606,0,0.089104,0.146444,0.253375,0.202955,-0.229283,516.054199,-583.926147,-3070.804443,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,110729,105620,103420,110593 -7.861773,-0.290232,0.266568,-0.944738,0.797848,0.265891,0.054578,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-22.969353,-1091.702026,-2897.02417,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,111599,105759,103622,109370 -7.866774,-0.292186,0.319547,-0.788732,1.093703,0.563874,0.053514,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-569.804749,-1634.63147,-2886.162842,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,112678,105766,103637,108269 -7.871775,-0.282176,0.24899,-0.67008,1.41297,0.816096,0.062028,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-1032.661865,-2220.526367,-2973.052979,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,113814,105802,103427,107307 -7.876776,-0.236766,0.211881,-0.748449,1.657742,1.060868,0.066285,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-1481.848267,-2669.712891,-3016.498291,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,114756,105759,103383,106452 -7.881777,-0.200145,0.173795,-0.77799,1.85356,1.283291,0.048193,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-1890.021729,-3029.061768,-2831.856445,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,115347,105904,103626,105509 -7.886778,-0.168895,0.167691,-0.655187,1.989781,1.455696,0.041807,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-2206.405029,-3279.043945,-2766.688965,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,115849,105902,103757,104878 -7.891779,-0.156199,0.166471,-0.507971,2.136644,1.604687,0.040743,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-2479.822754,-3548.55542,-2755.827637,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,116381,105909,103772,104324 -7.89678,-0.23823,0.130582,-0.589758,2.256902,1.71111,0.066285,0,0.094157,0.116067,0.20317,0.108756,-0.374636,-2767.252441,-3942.109375,-4499.951172,0,0,-0.150739,0.66922,-0.748811,-0.052563,-0.109014,0.007311,0.089533,0.334481,0,118806,104271,101922,105387 -7.901781,-0.343699,0.248014,-0.980139,1.980203,2.011221,0.18867,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-3414.317139,-3479.802979,-5140.865234,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,119631,102521,102390,105843 -7.906782,-0.435008,0.306363,-1.155676,1.793963,2.502893,0.346176,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-4316.595215,-3138.030762,-6748.333496,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121791,100000,102019,106882 -7.911783,-0.620799,0.340055,-1.686193,0.721224,2.054855,0.520709,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-3494.389404,-1169.42334,-8529.583008,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,120782,100000,101384,111454 -7.916784,-0.353221,0.550748,-1.860021,0.215717,2.282599,0.682471,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-3912.328125,-241.756042,-10180.49609,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121923,100000,101079,113615 -7.921785,-0.669627,0.512906,-1.980627,-0.030119,1.416319,0.886802,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-2322.599121,209.383224,-12265.86035,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121968,100000,100000,117741 -7.926786,-0.508006,0.554166,-2.263586,-0.135478,0.882078,0.983647,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-1342.201294,402.728607,-13254.23633,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121850,100000,100000,119971 -7.931787,-0.442576,0.437467,-2.230627,0.051826,1.024684,0.913408,0,0.147959,0.074754,0.137049,0.048981,-0.942309,-1628.919312,-5.221539,-18939.07227,0,0,-0.126976,0.712879,-0.785518,-0.032264,0.01091,0.025773,0.089533,0.334481,0,128230,100000,100000,124961 -7.936789,-0.423045,0.546354,-1.897131,0.10823,0.432975,0.884674,0,0.147959,0.074754,0.137049,0.048981,-0.942309,-543.060303,-108.729675,-18645.81836,0,0,-0.126976,0.712879,-0.785518,-0.032264,0.01091,0.025773,0.089533,0.334481,0,126954,100000,100000,125651 -7.94179,-0.493602,0.613248,-1.618811,0.321075,0.404241,0.908087,0,0.147959,0.074754,0.137049,0.048981,-0.942309,-490.329742,-499.326416,-18884.76563,0,0,-0.126976,0.712879,-0.785518,-0.032264,0.01091,0.025773,0.089533,0.334481,0,127531,100000,100000,125552 -7.946791,-0.524607,0.532438,-1.6005,0.255093,0.331873,0.991097,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,12.120502,-549.678711,-28058.23047,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136252,100000,100000,135177 -7.951792,-0.363719,0.34274,-1.571203,0.400892,0.249928,1.012381,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,162.500259,-817.237488,-28275.45508,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136524,100000,100000,135214 -7.956793,-0.309764,0.334928,-1.444738,0.407277,0.322295,0.988968,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,29.69739,-828.955444,-28036.50781,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136429,100000,100000,134831 -7.961794,-0.355906,0.356656,-1.242346,0.265735,0.427654,1.024088,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,-163.648056,-569.208557,-28394.92969,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136721,100000,100000,135256 -7.966795,-0.326854,0.356656,-1.019445,0.308304,0.401048,1.10284,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,-114.82341,-647.327942,-29198.66406,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,137554,100000,100000,136030 -7.971796,-0.24409,0.263639,-0.946203,0.202946,0.351029,1.166694,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,-23.03322,-453.982513,-29850.33984,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,137919,100000,100000,136965 -7.976797,-0.159617,0.141813,-0.937902,0.20401,0.468094,1.177336,0,0.204729,-0.035348,0.17397,0.017706,-2.66099,-539.754211,-341.890289,-39173.19141,0,0,-0.042927,0.807064,-0.773606,-0.030316,0.030759,-0.053054,0.089533,0.334481,0,138473,100000,100000,136710 -7.981798,-0.167918,0.186246,-0.868322,0.127386,0.463837,1.179464,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,-558.728638,-213.581131,-41034.28906,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,138364,100000,100000,136819 -7.986799,-0.211863,0.24777,-0.714025,0.096523,0.515984,1.198621,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,-654.424866,-156.944611,-41229.79297,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,138403,100000,100000,136780 -7.9918,-0.162303,0.245572,-0.767004,-0.07056,0.313781,1.225226,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,-283.357941,149.673843,-41501.32422,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137794,100000,100000,137527 -7.996801,-0.151316,0.258756,-0.889807,-0.102487,0.133927,1.199685,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,46.696327,208.263367,-41240.65234,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137406,100000,100000,137915 -8.001802,-0.200877,0.301969,-0.958654,-0.097166,-0.057633,1.144345,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,398.233398,198.498444,-40675.86719,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137064,100000,100000,138257 -8.006804,-0.32783,0.389127,-1.151037,0.031606,-0.081046,1.098583,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,441.199066,-37.812588,-40208.83203,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137257,100000,100000,138064 -8.011805,-0.361521,0.436734,-1.42301,-0.005642,0.102001,1.10284,0,0.097906,0.055357,0.019547,0.136141,-2.87144,-151.311539,260.18869,-40560.71094,0,0,-0.003315,0.863276,-0.776552,-0.02517,0.078358,-0.080783,0.089533,0.334481,0,137552,100000,100000,137769 -8.016806,-0.368357,0.514371,-1.429846,-0.020541,0.103065,1.099648,0,0.097906,0.055357,0.019547,0.136141,-2.87144,-153.264511,287.530457,-40528.12891,0,0,-0.003315,0.863276,-0.776552,-0.02517,0.078358,-0.080783,0.089533,0.334481,0,137531,100000,100000,137800 -8.021807,-0.375926,0.469449,-1.353674,-0.060982,0.008349,1.087941,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,136.696716,212.115463,-42505.72266,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137317,100000,100000,138014 -8.026808,-0.307078,0.409146,-1.233557,-0.049276,-0.003358,1.060271,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,158.179535,190.632629,-42223.33203,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137317,100000,100000,138014 -8.031809,-0.272898,0.376432,-1.091223,-0.005642,-0.073597,1.028345,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,287.076477,110.560303,-41897.49219,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137268,100000,100000,138063 -8.03681,-0.227,0.329557,-0.956701,-0.030119,-0.06934,1.004931,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,279.264526,155.478928,-41658.54688,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137155,100000,100000,138024 -8.041811,-0.220164,0.286832,-0.858557,0.016706,-0.090624,0.990032,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,318.324188,69.547646,-41506.48828,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137202,100000,100000,137977 -8.046812,-0.211863,0.266813,-0.819982,0.019899,-0.068276,0.988968,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,277.311554,63.688694,-41495.625,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137248,100000,100000,137931 -8.051813,-0.204539,0.250455,-0.812414,0.017771,-0.014,0.991097,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,177.709366,67.594658,-41517.34766,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137344,100000,100000,137835 -8.056814,-0.202586,0.27316,-0.806799,0.026285,0.074331,0.995353,0,0.075028,0.040852,0.096522,0.026617,-3.171982,40.722889,0.610975,-42530.99219,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137548,100000,100000,137631 -8.061815,-0.218699,0.325406,-0.846105,0.051826,0.170111,0.985775,0,0.075028,0.040852,0.096522,0.026617,-3.171982,-135.045654,-46.260635,-42433.23828,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137778,100000,100000,137415 -8.066816,-0.244822,0.37985,-1.060949,0.029477,0.029633,0.947463,0,0.075028,0.040852,0.096522,0.026617,-3.171982,122.748207,-5.247975,-42042.23438,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137479,100000,100000,137714 -8.071817,-0.288523,0.423795,-1.202551,0.06034,-0.033156,0.910215,0,0.075028,0.040852,0.096522,0.026617,-3.171982,237.974243,-61.884502,-41662.08984,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137420,100000,100000,137773 -8.076818,-0.336131,0.468717,-1.230383,0.02522,-0.00655,0.882546,0,0.075028,0.040852,0.096522,0.026617,-3.171982,189.149658,2.56396,-41379.69531,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137405,100000,100000,137788 -8.08182,-0.304393,0.451139,-1.218664,0.02522,0.043468,0.866582,0,0.075028,0.040852,0.096522,0.026617,-3.171982,97.359421,2.56396,-41216.77734,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137502,100000,100000,137701 -8.086821,-0.293162,0.437711,-1.113928,0.045441,0.06156,0.858068,0,0.075028,0.040852,0.096522,0.026617,-3.171982,64.158691,-34.542732,-41129.88672,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137572,100000,100000,137631 -8.091822,-0.266307,0.379605,-0.977941,0.035863,0.071138,0.837848,0,0.504875,-0.32476,0.427208,-0.259985,-4.725514,653.432068,-542.916016,-56778.56641,0,0,0.05686,0.943105,-0.759773,-0.02475,0.077667,-0.064775,0.089533,0.334481,0,137491,100000,100000,137712 -8.096823,-0.213084,0.320035,-0.891516,0.097588,0.055175,0.810178,0,0.053843,-0.032019,0.009677,0.022951,-4.558378,-83.494263,-136.967773,-54790.41016,0,0,0.087721,0.976527,-0.737882,-0.025765,0.044166,-0.054969,0.089533,0.334481,0,137822,100000,100000,137381 -8.101824,-0.199168,0.329313,-0.840002,0.096523,0.018991,0.782508,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,123.047142,-199.706177,-53887.27734,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137672,100000,100000,137519 -8.106825,-0.186473,0.298795,-0.806066,0.078432,0.007285,0.764417,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,144.529968,-166.505447,-53702.63672,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137617,100000,100000,137574 -8.111826,-0.197703,0.325162,-0.829504,-0.008835,-0.022514,0.762288,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,199.213501,-6.36078,-53680.91016,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137403,100000,100000,137788 -8.116827,-0.228221,0.353238,-0.911291,-0.034376,0.011541,0.754838,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,136.718033,40.510834,-53604.88281,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137418,100000,100000,137773 -8.121828,-0.260936,0.423307,-1.037512,-0.006706,-0.018257,0.723976,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,191.401566,-10.266747,-53289.90625,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137414,100000,100000,137777 -8.126829,-0.267527,0.428434,-1.110021,0.056083,-0.010807,0.682471,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,177.730682,-125.49279,-52866.31641,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137540,100000,100000,137645 -8.13183,-0.277293,0.448941,-1.136877,0.051826,-0.029963,0.645223,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,212.884399,-117.680855,-52486.17188,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137497,100000,100000,137688 -8.136831,-0.252146,0.459439,-1.102209,0.011385,0.004092,0.617553,0,-0.023052,0.123418,-0.103932,0.186339,-4.036829,-198.237488,321.060669,-47501.69141,0,0,0.091095,0.99048,-0.746279,-0.024262,0.08088,-0.06292,0.089533,0.334481,0,137470,100000,100000,137715 -8.141832,-0.24116,0.414762,-1.048742,-0.027991,0.005156,0.598397,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,117.511627,-66.476601,-53532.56641,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137541,100000,100000,137644 -8.146833,-0.238475,0.418668,-0.992102,-0.018413,-0.036349,0.556893,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,193.677994,-84.053452,-53108.97656,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137476,100000,100000,137695 -8.151834,-0.205027,0.369352,-0.916662,0.043312,-0.025706,0.515388,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,174.148148,-197.326508,-52685.38672,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137609,100000,100000,137562 -8.156836,-0.204295,0.35275,-0.869543,0.047569,-0.046991,0.482397,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,213.207825,-205.138443,-52348.6875,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137577,100000,100000,137594 -8.161837,-0.209666,0.354215,-0.881262,0.03267,0.009413,0.463241,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,109.699692,-177.796677,-52153.1875,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137654,100000,100000,137517 -8.166838,-0.198436,0.357145,-0.897375,-0.00245,0.021119,0.45047,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,88.216866,-113.348213,-52022.85156,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137611,100000,100000,137560 -8.171839,-0.215525,0.365689,-0.943518,-0.00245,0.00622,0.424929,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-154.451828,221.704422,-50483.07813,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137592,100000,100000,137727 -8.17684,-0.213572,0.392301,-1.020178,0.006064,-0.010807,0.391938,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-123.204086,206.080551,-50146.37891,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137577,100000,100000,137742 -8.181841,-0.233348,0.416715,-1.065832,0.024156,-0.000165,0.363203,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-142.733917,172.879837,-49853.125,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137629,100000,100000,137690 -8.186842,-0.242381,0.427701,-1.069738,0.000743,-0.001229,0.337662,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-140.780945,215.845474,-49592.45313,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137584,100000,100000,137735 -8.191843,-0.234812,0.421109,-1.053137,-0.005642,-0.005486,0.311056,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-132.969009,227.563385,-49320.92188,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137497,100000,100000,137686 -8.196844,-0.234324,0.422574,-1.001623,-0.000321,-0.011872,0.278065,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-121.251099,217.798462,-48984.22266,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137495,100000,100000,137688 -8.201845,-0.221629,0.403775,-0.959387,0.008193,-0.019321,0.249331,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-107.580215,202.174591,-48690.96875,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137497,100000,100000,137686 -8.206846,-0.20698,0.387662,-0.933752,0.01245,-0.016128,0.225918,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-113.439163,194.362656,-48452.01953,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137511,100000,100000,137672 -8.211847,-0.211375,0.385465,-0.928137,0.005,-0.002294,0.207827,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-138.827957,208.033539,-48267.37891,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137524,100000,100000,137663 -8.216848,-0.219187,0.386686,-0.946691,-0.001385,-0.00655,0.193992,0,0.058494,-0.04663,-0.020143,0.013487,-4.774475,-24.944469,27.292582,-50707.17578,0,0,0.125816,1.037905,-0.727206,-0.023742,0.078637,-0.060117,0.089533,0.334481,0,137591,100000,100000,137596 -8.221849,-0.223338,0.400113,-0.982092,0.001807,-0.010807,0.178028,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-99.135567,108.01194,-50392.55469,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137585,100000,100000,137602 -8.226851,-0.227488,0.402799,-1.013586,0.006064,-0.00655,0.158872,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-106.947502,100.200005,-50197.05078,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137600,100000,100000,137587 -8.231852,-0.223582,0.405484,-1.025061,-0.003514,-0.009743,0.139716,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-101.088554,117.776855,-50001.55078,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137577,100000,100000,137610 -8.236853,-0.216502,0.390836,-1.004553,0.000743,-0.008679,0.118432,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-103.041534,109.96492,-49784.32422,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137588,100000,100000,137601 -8.241854,-0.202586,0.354947,-0.981115,-0.00245,-0.009743,0.099276,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-101.088554,115.823868,-49588.82031,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137580,100000,100000,137609 -8.246855,-0.179148,0.311979,-0.961096,0.001807,-0.007615,0.081184,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-104.994522,108.01194,-49404.17969,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137591,100000,100000,137598 -8.251856,-0.15742,0.264127,-0.954748,0.000743,-0.00655,0.067349,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-119.135727,103.400543,-49151.06641,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137610,100000,100000,137579 -8.256857,-0.131053,0.212613,-0.961828,0.003936,-0.007615,0.056706,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,97.541595,-49042.45313,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137610,100000,100000,137571 -8.261858,-0.10615,0.158658,-0.980139,0.000743,-0.007615,0.049257,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,103.400543,-48966.42578,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137604,100000,100000,137577 -8.266859,-0.080271,0.110318,-0.998693,0.002872,-0.007615,0.043936,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,99.494576,-48912.11719,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137608,100000,100000,137573 -8.27186,-0.061229,0.069059,-1.009436,0.000743,-0.007615,0.038615,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,103.400543,-48857.8125,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137604,100000,100000,137577 -8.276861,-0.045359,0.038785,-1.006262,0.002872,-0.007615,0.034358,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,99.494576,-48814.36719,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137608,100000,100000,137573 -8.281862,-0.038279,0.02609,-0.994299,0.000743,-0.00655,0.029037,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-119.135727,103.400543,-48760.05859,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137615,100000,100000,137584 -8.286863,-0.037791,0.026822,-0.981604,-0.001385,-0.009743,0.022651,0,0.004473,-0.008908,-0.072564,0.051306,-4.781736,-115.284752,96.694389,-49032.61328,0,0,0.131457,1.043312,-0.721488,-0.023576,0.077037,-0.060214,0.089533,0.334481,0,137618,100000,100000,137581 -8.291864,-0.04365,0.037564,-0.974279,-0.001385,-0.005486,0.01733,0,-0.007606,0.020257,-0.086086,0.080552,-4.721994,-147.910294,150.36525,-48368.59766,0,0,0.130634,1.042654,-0.722474,-0.023579,0.07848,-0.060296,0.089533,0.334481,0,137597,100000,100000,137602 -8.296865,-0.048777,0.0444,-0.978918,-0.004578,-0.008679,0.013073,0,-0.007606,0.020257,-0.086086,0.080552,-4.721994,-142.051346,156.224197,-48325.15234,0,0,0.130634,1.042654,-0.722474,-0.023579,0.07848,-0.060296,0.089533,0.334481,0,137585,100000,100000,137614 -8.301867,-0.050975,0.046354,-0.989904,-0.004578,-0.007615,0.010945,0,-0.005951,0.017183,-0.087077,0.083013,-4.690295,-145.823639,160.740372,-47979.91016,0,0,0.129413,1.041805,-0.72399,-0.023314,0.081127,-0.06583,0.089533,0.334481,0,137642,100000,100000,137671 -8.306868,-0.053904,0.042203,-0.99967,-0.006706,-0.009743,0.010945,0,-0.005951,0.017183,-0.087077,0.083013,-4.690295,-141.917679,164.646332,-47979.91016,0,0,0.129413,1.041805,-0.72399,-0.023314,0.081127,-0.06583,0.089533,0.334481,0,137634,100000,100000,137679 -8.311869,-0.04951,0.029508,-0.99967,-0.004578,-0.007615,0.010945,0,-0.005951,0.017183,-0.087077,0.083013,-4.690295,-145.823639,160.740372,-47979.91016,0,0,0.129413,1.041805,-0.72399,-0.023314,0.081127,-0.06583,0.089533,0.334481,0,137642,100000,100000,137671 diff --git a/controls/model/loggingAnalysis/logFiles/logData1.csv b/controls/model/loggingAnalysis/logFiles/logData1.csv deleted file mode 100644 index b824bc492610e14ccf6acc042a8451f122b98be3..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/logFiles/logData1.csv +++ /dev/null @@ -1,846 +0,0 @@ -time,accel_x,accel_y,accel_z,gyro_x,gyro_y,gyro_z,Altitude PID-Correction,X pos PID-Correction,Y pos PID-Correction,Pitch PID-Correction,Roll PID-Correction,Yaw PID-Correction,Pitch Rate PID-Correction,Roll Rate PID-Correction,Yaw Rate PID-Correction,Pitch-Constant,Roll-Constant,Yaw-Constant,VRPN X-Constant,VRPN Y-Constant,VRPN Alt-Constant,VRPN Pitch-Constant,VRPN Roll-Constant,X Setpoint-Constant,Y Setpoint-Constant,Alt Setpoint-Constant,Signal Mixer-PWM 0,Signal Mixer-PWM 1,Signal Mixer-PWM 2,Signal Mixer-PWM 3 -4.090967,-0.029734,0.001676,-0.983801,-0.006706,-0.008679,-0.00289,0,0,0,0.004518,0.023085,0,24.217617,54.670601,29.4963,0,0,-0.170938,0.089533,0.334481,-0.058551,-0.004518,-0.023085,0.089533,0.334481,0,107530,107638,107698,107688 -4.095968,-0.029734,0.001676,-0.983801,-0.006706,-0.008679,-0.00289,0,0,0,0.004518,0.023085,0,24.217617,54.670601,29.4963,0,0,-0.170938,0.089533,0.334481,-0.058551,-0.004518,-0.023085,0.089533,0.334481,0,107469,107577,107637,107627 -4.100969,-0.02949,0.001676,-0.983068,-0.006706,-0.008679,-0.00289,0,0,0,0.004518,0.023085,0,24.217617,54.670601,29.4963,0,0,-0.170938,0.089533,0.334481,-0.058551,-0.004518,-0.023085,0.089533,0.334481,0,107469,107577,107637,107627 -4.10597,-0.029734,0.001676,-0.98258,-0.006706,-0.008679,-0.00289,0,0,0,0.004518,0.023085,0,24.217617,54.670601,29.4963,0,0,-0.170938,0.089533,0.334481,-0.058551,-0.004518,-0.023085,0.089533,0.334481,0,107469,107577,107637,107627 -4.110971,-0.029979,0.00192,-0.982092,-0.006706,-0.008679,-0.00289,0,0,0,0.004518,0.023085,0,24.217617,54.670601,29.4963,0,0,-0.170938,0.089533,0.334481,-0.058551,-0.004518,-0.023085,0.089533,0.334481,0,107469,107577,107637,107627 -4.115973,-0.029979,0.001676,-0.981604,-0.006706,-0.008679,-0.00289,0,0,0,0.004518,0.023085,0,24.217617,54.670601,29.4963,0,0,-0.170938,0.089533,0.334481,-0.058551,-0.004518,-0.023085,0.089533,0.334481,0,107469,107577,107637,107627 -4.120974,-0.029979,0.002164,-0.982092,-0.006706,-0.008679,-0.00289,0,0,0,0.004518,0.023085,0,24.217617,54.670601,29.4963,0,0,-0.170938,0.089533,0.334481,-0.058551,-0.004518,-0.023085,0.089533,0.334481,0,107481,107589,107649,107639 -4.125975,-0.029246,0.002408,-0.983312,-0.006706,-0.008679,-0.00289,0,0.001136,0.000923,0.006086,0.024298,0.011051,27.095308,56.896408,142.275879,0,0,-0.171172,0.089615,0.334414,-0.058536,-0.00495,-0.023374,0.089533,0.334481,0,107363,107702,107762,107531 -4.130976,-0.029734,0.00192,-0.98258,-0.006706,-0.008679,-0.00289,0,-0.000493,-0.000367,0.004126,0.022877,0.004815,23.497805,54.289337,78.632347,0,0,-0.171208,0.089602,0.33442,-0.058557,-0.004618,-0.023244,0.089533,0.334481,0,107433,107637,107699,107589 -4.135977,-0.029979,0.00192,-0.982824,-0.006706,-0.008679,-0.00289,0,0.00024,0.00017,0.005345,0.023616,0.004603,25.734694,55.645031,76.468994,0,0,-0.171215,0.089607,0.334417,-0.058538,-0.005105,-0.023446,0.089533,0.334481,0,107432,107636,107696,107594 -4.140978,-0.029734,0.00192,-0.982336,-0.006706,-0.008679,-0.00289,0,0.00024,0.00017,0.005345,0.023616,0.004603,25.734694,55.645031,76.468994,0,0,-0.171215,0.089607,0.334417,-0.058538,-0.005105,-0.023446,0.089533,0.334481,0,107428,107632,107692,107590 -4.145979,-0.029979,0.002164,-0.982092,-0.006706,-0.008679,-0.00289,0,0.00024,0.00017,0.005345,0.023616,0.004603,25.734694,55.645031,76.468994,0,0,-0.171215,0.089607,0.334417,-0.058538,-0.005105,-0.023446,0.089533,0.334481,0,107428,107632,107692,107590 -4.15098,-0.030223,0.002164,-0.981848,-0.006706,-0.008679,-0.00289,0,0.00024,0.00017,0.005345,0.023616,0.004603,25.734694,55.645031,76.468994,0,0,-0.171215,0.089607,0.334417,-0.058538,-0.005105,-0.023446,0.089533,0.334481,0,107428,107632,107692,107590 -4.155981,-0.030223,0.001676,-0.982336,-0.005642,-0.008679,-0.00289,0,0.00024,0.00017,0.005345,0.023616,0.004603,25.734694,53.692047,76.468994,0,0,-0.171215,0.089607,0.334417,-0.058538,-0.005105,-0.023446,0.089533,0.334481,0,107430,107634,107690,107588 -4.160982,-0.029979,0.001432,-0.982092,-0.006706,-0.008679,-0.00289,0,-0.000869,-0.000633,0.003984,0.022185,-0.003077,23.237917,53.018921,-1.905351,0,0,-0.171058,0.08955,0.334458,-0.058538,-0.004853,-0.022818,0.089533,0.334481,0,107511,107554,107613,107664 -4.165983,-0.029734,0.001676,-0.981848,-0.006706,-0.007615,-0.00289,0,0.000561,0.000324,0.005143,0.02335,0.002935,23.411215,55.156509,59.448891,0,0,-0.171091,0.089586,0.334444,-0.058545,-0.004582,-0.023025,0.089533,0.334481,0,107434,107600,107664,107592 -4.170984,-0.029734,0.002652,-0.981848,-0.005642,-0.007615,-0.00289,0,0.000561,0.000324,0.005143,0.02335,0.002935,23.411215,53.203526,59.448891,0,0,-0.171091,0.089586,0.334444,-0.058545,-0.004582,-0.023025,0.089533,0.334481,0,107436,107602,107662,107590 -4.175985,-0.02949,0.00192,-0.981848,-0.005642,-0.007615,-0.00289,0,0.000561,0.000324,0.005143,0.02335,0.002935,23.411215,53.203526,59.448891,0,0,-0.171091,0.089586,0.334444,-0.058545,-0.004582,-0.023025,0.089533,0.334481,0,107436,107602,107662,107590 -4.180986,-0.02949,0.00192,-0.98258,-0.005642,-0.008679,-0.00289,0,0.000561,0.000324,0.005143,0.02335,0.002935,25.364199,53.203526,59.448891,0,0,-0.171091,0.089586,0.334444,-0.058545,-0.004582,-0.023025,0.089533,0.334481,0,107434,107604,107660,107592 -4.185987,-0.02949,0.002164,-0.983068,-0.006706,-0.007615,-0.00289,0,0.000561,0.000324,0.005143,0.02335,0.002935,23.411215,55.156509,59.448891,0,0,-0.171091,0.089586,0.334444,-0.058545,-0.004582,-0.023025,0.089533,0.334481,0,107432,107598,107662,107590 -4.190989,-0.029246,0.002896,-0.983557,-0.006706,-0.007615,-0.00289,0,0.000561,0.000324,0.005143,0.02335,0.002935,23.411215,55.156509,59.448891,0,0,-0.171091,0.089586,0.334444,-0.058545,-0.004582,-0.023025,0.089533,0.334481,0,107432,107598,107662,107590 -4.19599,-0.028758,0.002652,-0.983557,-0.005642,-0.007615,-0.00289,0,-0.001053,-0.000417,0.003865,0.022734,-0.004452,21.066961,52.073772,-15.941745,0,0,-0.170946,0.089525,0.334466,-0.058553,-0.004918,-0.023151,0.089533,0.334481,0,107513,107524,107586,107660 -4.200991,-0.029246,0.002896,-0.983312,-0.005642,-0.008679,-0.00289,0,0.000601,0.000268,0.005865,0.02332,0.006077,26.689104,53.149609,91.520851,0,0,-0.171173,0.089573,0.33444,-0.058565,-0.005264,-0.023052,0.089533,0.334481,0,107399,107636,107688,107559 -4.205992,-0.029246,0.002164,-0.983801,-0.005642,-0.008679,-0.00289,0,0.000601,0.000268,0.005865,0.02332,0.006077,26.689104,53.149609,91.520851,0,0,-0.171173,0.089573,0.33444,-0.058565,-0.005264,-0.023052,0.089533,0.334481,0,107407,107644,107696,107567 -4.210993,-0.029734,0.002164,-0.984289,-0.006706,-0.008679,-0.00289,0,0.000601,0.000268,0.005865,0.02332,0.006077,26.689104,55.102592,91.520851,0,0,-0.171173,0.089573,0.33444,-0.058565,-0.005264,-0.023052,0.089533,0.334481,0,107405,107642,107698,107569 -4.215994,-0.030467,0.00192,-0.983801,-0.006706,-0.008679,-0.00289,0,0.000601,0.000268,0.005865,0.02332,0.006077,26.689104,55.102592,91.520851,0,0,-0.171173,0.089573,0.33444,-0.058565,-0.005264,-0.023052,0.089533,0.334481,0,107405,107642,107698,107569 -4.220995,-0.030223,0.002896,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000601,0.000268,0.005865,0.02332,0.006077,24.736122,55.102592,91.520851,0,0,-0.171173,0.089573,0.33444,-0.058565,-0.005264,-0.023052,0.089533,0.334481,0,107407,107640,107700,107567 -4.225996,-0.030711,0.002164,-0.983557,-0.006706,-0.007615,-0.00289,0,0.000601,0.000268,0.005865,0.02332,0.006077,24.736122,55.102592,91.520851,0,0,-0.171173,0.089573,0.33444,-0.058565,-0.005264,-0.023052,0.089533,0.334481,0,107407,107640,107700,107567 -4.230997,-0.030711,0.002164,-0.983068,-0.006706,-0.007615,-0.00289,0,0.000674,0.000403,0.001428,0.019424,0.017192,16.593538,47.953426,204.951996,0,0,-0.171601,0.089701,0.334368,-0.058442,-0.000754,-0.019021,0.089533,0.334481,0,107314,107757,107820,107443 -4.235998,-0.030711,0.002164,-0.98258,-0.006706,-0.007615,-0.00289,0,-0.002798,-0.001363,0.00235,0.021449,-0.012656,18.286503,51.668179,-99.672508,0,0,-0.171112,0.089517,0.334456,-0.058583,-0.005148,-0.022812,0.089533,0.334481,0,107613,107450,107517,107753 -4.240999,-0.030711,0.002408,-0.98258,-0.006706,-0.007615,-0.00289,0,-0.002798,-0.001363,0.00235,0.021449,-0.012656,18.286503,51.668179,-99.672508,0,0,-0.171112,0.089517,0.334456,-0.058583,-0.005148,-0.022812,0.089533,0.334481,0,107613,107450,107517,107753 -4.246,-0.030711,0.002652,-0.982336,-0.006706,-0.007615,-0.00289,0,-0.002798,-0.001363,0.00235,0.021449,-0.012656,18.286503,51.668179,-99.672508,0,0,-0.171112,0.089517,0.334456,-0.058583,-0.005148,-0.022812,0.089533,0.334481,0,107613,107450,107517,107753 -4.251001,-0.030711,0.002652,-0.982336,-0.006706,-0.007615,-0.00289,0,-0.002798,-0.001363,0.00235,0.021449,-0.012656,18.286503,51.668179,-99.672508,0,0,-0.171112,0.089517,0.334456,-0.058583,-0.005148,-0.022812,0.089533,0.334481,0,107607,107444,107511,107747 -4.256002,-0.031199,0.002408,-0.982336,-0.006706,-0.007615,-0.00289,0,-0.002798,-0.001363,0.00235,0.021449,-0.012656,18.286503,51.668179,-99.672508,0,0,-0.171112,0.089517,0.334456,-0.058583,-0.005148,-0.022812,0.089533,0.334481,0,107607,107444,107511,107747 -4.261003,-0.031199,0.00192,-0.982824,-0.006706,-0.007615,-0.00289,0,-0.002798,-0.001363,0.00235,0.021449,-0.012656,18.286503,51.668179,-99.672508,0,0,-0.171112,0.089517,0.334456,-0.058583,-0.005148,-0.022812,0.089533,0.334481,0,107607,107444,107511,107747 -4.266005,-0.030711,0.002164,-0.982824,-0.006706,-0.007615,-0.00289,0,-0.002798,-0.001363,0.00235,0.021449,-0.012656,18.286503,51.668179,-99.672508,0,0,-0.171112,0.089517,0.334456,-0.058583,-0.005148,-0.022812,0.089533,0.334481,0,107607,107444,107511,107747 -4.271006,-0.030223,0.002652,-0.98258,-0.006706,-0.008679,-0.00289,0,0.00094,0.000481,0.006028,0.022974,0.000852,26.989687,54.467583,38.187565,0,0,-0.171072,0.089512,0.334457,-0.058602,-0.005088,-0.022493,0.089533,0.334481,0,107458,107588,107643,107621 -4.276007,-0.030223,0.002408,-0.981848,-0.006706,-0.008679,-0.00289,0,-0.000407,-0.000245,0.004466,0.022135,0.001687,24.122751,52.927185,46.71479,0,0,-0.171056,0.089497,0.334472,-0.058576,-0.004873,-0.02238,0.089533,0.334481,0,107461,107602,107660,107615 -4.281008,-0.029979,0.002164,-0.981848,-0.006706,-0.008679,-0.00289,0,0.000635,0.000449,0.006068,0.023189,0.005514,27.062206,54.86203,85.774704,0,0,-0.171133,0.089532,0.334446,-0.058594,-0.005433,-0.02274,0.089533,0.334481,0,107417,107642,107698,107581 -4.286009,-0.029979,0.002164,-0.982092,-0.006706,-0.008679,-0.00289,0,0.000635,0.000449,0.006068,0.023189,0.005514,27.062206,54.86203,85.774704,0,0,-0.171133,0.089532,0.334446,-0.058594,-0.005433,-0.02274,0.089533,0.334481,0,107417,107642,107698,107581 -4.29101,-0.029979,0.002408,-0.981604,-0.006706,-0.008679,-0.00289,0,0.000635,0.000449,0.006068,0.023189,0.005514,27.062206,54.86203,85.774704,0,0,-0.171133,0.089532,0.334446,-0.058594,-0.005433,-0.02274,0.089533,0.334481,0,107417,107642,107698,107581 -4.296011,-0.029979,0.002408,-0.981604,-0.006706,-0.007615,-0.00289,0,0.000635,0.000449,0.006068,0.023189,0.005514,25.109222,54.86203,85.774704,0,0,-0.171133,0.089532,0.334446,-0.058594,-0.005433,-0.02274,0.089533,0.334481,0,107421,107643,107702,107581 -4.301012,-0.030223,0.002652,-0.982336,-0.006706,-0.008679,-0.00289,0,0.000635,0.000449,0.006068,0.023189,0.005514,27.062206,54.86203,85.774704,0,0,-0.171133,0.089532,0.334446,-0.058594,-0.005433,-0.02274,0.089533,0.334481,0,107419,107644,107700,107583 -4.306013,-0.030223,0.002652,-0.98258,-0.006706,-0.008679,-0.00289,0,0.000635,0.000449,0.006068,0.023189,0.005514,27.062206,54.86203,85.774704,0,0,-0.171133,0.089532,0.334446,-0.058594,-0.005433,-0.02274,0.089533,0.334481,0,107419,107644,107700,107583 -4.311014,-0.029979,0.002408,-0.98258,-0.006706,-0.008679,-0.00289,0,0.000923,0.000318,0.001383,0.019366,0.018101,18.46483,47.846436,214.235352,0,0,-0.17161,0.089699,0.334377,-0.05845,-0.00046,-0.019048,0.089533,0.334481,0,107306,107771,107830,107439 -4.316015,-0.030223,0.002652,-0.982336,-0.006706,-0.008679,-0.00289,0,-0.002356,-0.000687,0.002717,0.021948,-0.007129,20.913271,52.583965,-43.262737,0,0,-0.171235,0.089552,0.334419,-0.058582,-0.005074,-0.022635,0.089533,0.334481,0,107555,107511,107574,107702 -4.321016,-0.030223,0.002164,-0.982336,-0.006706,-0.008679,-0.00289,0,0.001279,0.000218,0.006516,0.022877,0.006486,27.884125,54.289654,95.687172,0,0,-0.171274,0.089584,0.334421,-0.058596,-0.005237,-0.022659,0.089533,0.334481,0,107408,107655,107708,107572 -4.326017,-0.030223,0.002164,-0.983068,-0.006706,-0.007615,-0.00289,0,0.001279,0.000218,0.006516,0.022877,0.006486,25.931141,54.289654,95.687172,0,0,-0.171274,0.089584,0.334421,-0.058596,-0.005237,-0.022659,0.089533,0.334481,0,107410,107653,107710,107570 -4.331018,-0.030223,0.00192,-0.982824,-0.006706,-0.007615,-0.00289,0,0.001279,0.000218,0.006516,0.022877,0.006486,25.931141,54.289654,95.687172,0,0,-0.171274,0.089584,0.334421,-0.058596,-0.005237,-0.022659,0.089533,0.334481,0,107410,107653,107710,107570 -4.33602,-0.030711,0.00192,-0.983068,-0.006706,-0.007615,-0.00289,0,0.001279,0.000218,0.006516,0.022877,0.006486,25.931141,54.289654,95.687172,0,0,-0.171274,0.089584,0.334421,-0.058596,-0.005237,-0.022659,0.089533,0.334481,0,107410,107653,107710,107570 -4.341021,-0.030223,0.002408,-0.983068,-0.006706,-0.007615,-0.00289,0,0.001279,0.000218,0.006516,0.022877,0.006486,25.931141,54.289654,95.687172,0,0,-0.171274,0.089584,0.334421,-0.058596,-0.005237,-0.022659,0.089533,0.334481,0,107408,107651,107708,107568 -4.346022,-0.029734,0.002652,-0.98258,-0.006706,-0.007615,-0.00289,0,0.001279,0.000218,0.006516,0.022877,0.006486,25.931141,54.289654,95.687172,0,0,-0.171274,0.089584,0.334421,-0.058596,-0.005237,-0.022659,0.089533,0.334481,0,107408,107651,107708,107568 -4.351023,-0.02949,0.002408,-0.982336,-0.006706,-0.007615,-0.00289,0,0.001279,0.000218,0.006516,0.022877,0.006486,25.931141,54.289654,95.687172,0,0,-0.171274,0.089584,0.334421,-0.058596,-0.005237,-0.022659,0.089533,0.334481,0,107408,107651,107708,107568 -4.356024,-0.029979,0.002652,-0.982824,-0.006706,-0.008679,-0.00289,0,-0.000735,-0.000242,0.004196,0.022128,0.004106,23.627007,52.913918,71.403427,0,0,-0.171249,0.089564,0.334433,-0.058586,-0.004931,-0.02237,0.089533,0.334481,0,107436,107626,107684,107589 -4.361025,-0.02949,0.002652,-0.983068,-0.006706,-0.008679,-0.00289,0,0.000734,0.000336,0.005796,0.023231,0.009761,26.563646,54.939568,129.119568,0,0,-0.171434,0.089666,0.334379,-0.058575,-0.005062,-0.022895,0.089533,0.334481,0,107370,107681,107738,107533 -4.366026,-0.02949,0.002408,-0.983312,-0.006706,-0.008679,-0.00289,0,0.000734,0.000336,0.005796,0.023231,0.009761,26.563646,54.939568,129.119568,0,0,-0.171434,0.089666,0.334379,-0.058575,-0.005062,-0.022895,0.089533,0.334481,0,107370,107681,107738,107533 -4.371027,-0.02949,0.002408,-0.983312,-0.006706,-0.008679,-0.00289,0,-0.001478,-0.000827,0.00354,0.022032,-0.007458,22.422613,52.738903,-46.618023,0,0,-0.171111,0.089578,0.33443,-0.058567,-0.005017,-0.02286,0.089533,0.334481,0,107552,107504,107564,107702 -4.376028,-0.029246,0.002164,-0.982824,-0.006706,-0.008679,-0.00289,0,-0.001478,-0.000827,0.00354,0.022032,-0.007458,22.422613,52.738903,-46.618023,0,0,-0.171111,0.089578,0.33443,-0.058567,-0.005017,-0.02286,0.089533,0.334481,0,107552,107504,107564,107702 -4.381029,-0.029246,0.002408,-0.981848,-0.006706,-0.008679,-0.00289,0,-0.001478,-0.000827,0.00354,0.022032,-0.007458,22.422613,52.738903,-46.618023,0,0,-0.171111,0.089578,0.33443,-0.058567,-0.005017,-0.02286,0.089533,0.334481,0,107552,107504,107564,107702 -4.38603,-0.029734,0.002652,-0.982092,-0.006706,-0.008679,-0.00289,0,-0.001478,-0.000827,0.00354,0.022032,-0.007458,22.422613,52.738903,-46.618023,0,0,-0.171111,0.089578,0.33443,-0.058567,-0.005017,-0.02286,0.089533,0.334481,0,107553,107505,107565,107703 -4.391031,-0.029734,0.002652,-0.982824,-0.006706,-0.008679,-0.00289,0,-0.001478,-0.000827,0.00354,0.022032,-0.007458,22.422613,52.738903,-46.618023,0,0,-0.171111,0.089578,0.33443,-0.058567,-0.005017,-0.02286,0.089533,0.334481,0,107553,107505,107565,107703 -4.396032,-0.029734,0.002652,-0.983557,-0.006706,-0.008679,-0.00289,0,-0.001478,-0.000827,0.00354,0.022032,-0.007458,22.422613,52.738903,-46.618023,0,0,-0.171111,0.089578,0.33443,-0.058567,-0.005017,-0.02286,0.089533,0.334481,0,107553,107505,107565,107703 -4.401033,-0.029734,0.002896,-0.98258,-0.006706,-0.008679,-0.00289,0,-0.001478,-0.000827,0.00354,0.022032,-0.007458,22.422613,52.738903,-46.618023,0,0,-0.171111,0.089578,0.33443,-0.058567,-0.005017,-0.02286,0.089533,0.334481,0,107553,107505,107565,107703 -4.406034,-0.029734,0.002164,-0.98258,-0.006706,-0.008679,-0.00289,0,0.000591,0.000338,0.005378,0.023779,0.003902,25.796772,55.945023,69.316902,0,0,-0.171136,0.089583,0.334427,-0.058552,-0.004787,-0.023441,0.089533,0.334481,0,107438,107629,107689,107602 -4.411036,-0.029979,0.002164,-0.982824,-0.006706,-0.007615,-0.00289,0,-0.000362,-0.00032,0.004464,0.022541,-0.001109,22.165171,53.67292,18.17816,0,0,-0.170975,0.08955,0.33447,-0.058527,-0.004825,-0.022861,0.089533,0.334481,0,107495,107576,107639,107647 -4.416037,-0.029979,0.002164,-0.98258,-0.006706,-0.007615,-0.00289,0,-0.000362,-0.00032,0.004464,0.022541,-0.001109,22.165171,53.67292,18.17816,0,0,-0.170975,0.08955,0.33447,-0.058527,-0.004825,-0.022861,0.089533,0.334481,0,107495,107576,107639,107647 -4.421038,-0.029734,0.00192,-0.982824,-0.006706,-0.007615,-0.00289,0,0.000319,0.000375,0.005101,0.023766,0.00369,23.334517,55.921402,67.152649,0,0,-0.171041,0.089564,0.334451,-0.058544,-0.004782,-0.023392,0.089533,0.334481,0,107443,107624,107689,107602 -4.426039,-0.029734,0.00192,-0.982824,-0.006706,-0.007615,-0.00289,0,0.000319,0.000375,0.005101,0.023766,0.00369,23.334517,55.921402,67.152649,0,0,-0.171041,0.089564,0.334451,-0.058544,-0.004782,-0.023392,0.089533,0.334481,0,107430,107611,107676,107589 -4.43104,-0.029246,0.00192,-0.983068,-0.006706,-0.007615,-0.00289,0,0.000319,0.000375,0.005101,0.023766,0.00369,23.334517,55.921402,67.152649,0,0,-0.171041,0.089564,0.334451,-0.058544,-0.004782,-0.023392,0.089533,0.334481,0,107430,107611,107676,107589 -4.436041,-0.029246,0.002164,-0.98258,-0.006706,-0.007615,-0.00289,0,0.000319,0.000375,0.005101,0.023766,0.00369,23.334517,55.921402,67.152649,0,0,-0.171041,0.089564,0.334451,-0.058544,-0.004782,-0.023392,0.089533,0.334481,0,107430,107611,107676,107589 -4.441042,-0.02949,0.002408,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000319,0.000375,0.005101,0.023766,0.00369,23.334517,55.921402,67.152649,0,0,-0.171041,0.089564,0.334451,-0.058544,-0.004782,-0.023392,0.089533,0.334481,0,107430,107611,107676,107589 -4.446043,-0.029979,0.002164,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000319,0.000375,0.005101,0.023766,0.00369,23.334517,55.921402,67.152649,0,0,-0.171041,0.089564,0.334451,-0.058544,-0.004782,-0.023392,0.089533,0.334481,0,107430,107611,107676,107589 -4.451044,-0.029979,0.002164,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000319,0.000375,0.005101,0.023766,0.00369,23.334517,55.921402,67.152649,0,0,-0.171041,0.089564,0.334451,-0.058544,-0.004782,-0.023392,0.089533,0.334481,0,107436,107617,107682,107595 -4.456045,-0.029979,0.002164,-0.981848,-0.006706,-0.007615,-0.00289,0,0.00175,0.000567,0.002079,0.020211,0.017875,17.789684,49.3974,211.921005,0,0,-0.171385,0.089698,0.3344,-0.058421,-0.00033,-0.019644,0.089533,0.334481,0,107303,107763,107826,107438 -4.461046,-0.029979,0.002408,-0.981604,-0.006706,-0.007615,-0.00289,0,-0.001562,-0.000565,0.00309,0.02204,-0.002377,19.643753,52.75293,5.235507,0,0,-0.171086,0.089563,0.334453,-0.058553,-0.004652,-0.022605,0.089533,0.334481,0,107505,107555,107621,107650 -4.466047,-0.030223,0.002164,-0.981848,-0.006706,-0.007615,-0.00289,0,0.000282,0.000163,0.005463,0.02336,0.002304,23.998589,55.176155,53.008457,0,0,-0.171085,0.089543,0.334455,-0.058546,-0.005181,-0.023198,0.089533,0.334481,0,107450,107604,107667,107609 -4.471048,-0.030223,0.00192,-0.981604,-0.006706,-0.007615,-0.00289,0,0.000142,0.000089,0.005029,0.023065,0.004999,23.202473,54.633503,80.516632,0,0,-0.171142,0.08956,0.334445,-0.058548,-0.004887,-0.022976,0.089533,0.334481,0,107421,107629,107691,107577 -4.476049,-0.030467,0.001676,-0.981848,-0.005642,-0.007615,-0.00289,0,0.000142,0.000089,0.005029,0.023065,0.004999,23.202473,52.680519,80.516632,0,0,-0.171142,0.08956,0.334445,-0.058548,-0.004887,-0.022976,0.089533,0.334481,0,107423,107631,107689,107575 -4.48105,-0.029979,0.002408,-0.982092,-0.005642,-0.007615,-0.00289,0,0.000142,0.000089,0.005029,0.023065,0.004999,23.202473,52.680519,80.516632,0,0,-0.171142,0.08956,0.334445,-0.058548,-0.004887,-0.022976,0.089533,0.334481,0,107423,107631,107689,107575 -4.486052,-0.029734,0.002164,-0.982092,-0.005642,-0.007615,-0.00289,0,0.000142,0.000089,0.005029,0.023065,0.004999,23.202473,52.680519,80.516632,0,0,-0.171142,0.08956,0.334445,-0.058548,-0.004887,-0.022976,0.089533,0.334481,0,107423,107631,107689,107575 -4.491053,-0.030223,0.002408,-0.981848,-0.005642,-0.008679,-0.00289,0,0.000142,0.000089,0.005029,0.023065,0.004999,25.155457,52.680519,80.516632,0,0,-0.171142,0.08956,0.334445,-0.058548,-0.004887,-0.022976,0.089533,0.334481,0,107421,107632,107688,107577 -4.496054,-0.030223,0.002652,-0.982336,-0.005642,-0.007615,-0.00289,0,0.000142,0.000089,0.005029,0.023065,0.004999,23.202473,52.680519,80.516632,0,0,-0.171142,0.08956,0.334445,-0.058548,-0.004887,-0.022976,0.089533,0.334481,0,107426,107634,107692,107578 -4.501055,-0.030223,0.002896,-0.983312,-0.005642,-0.007615,-0.00289,0,0.000276,0.000459,0.005644,0.023718,0.007451,24.331057,53.878738,105.538925,0,0,-0.171232,0.089584,0.334409,-0.058558,-0.005368,-0.023258,0.089533,0.334481,0,107399,107658,107718,107555 -4.506056,-0.030223,0.002896,-0.983801,-0.005642,-0.007615,-0.00289,0,-0.000309,-0.000386,0.004675,0.022489,0.000644,22.552645,51.623371,36.065758,0,0,-0.171105,0.089554,0.334441,-0.058582,-0.004983,-0.022874,0.089533,0.334481,0,107472,107589,107648,107621 -4.511057,-0.029734,0.002408,-0.983801,-0.005642,-0.007615,-0.00289,0,-0.000138,0.000263,0.004952,0.023061,0.004389,23.061745,52.67326,74.293793,0,0,-0.171142,0.089536,0.334432,-0.058584,-0.00509,-0.022797,0.089533,0.334481,0,107432,107627,107686,107584 -4.516058,-0.029734,0.002408,-0.98258,-0.005642,-0.007615,-0.00289,0,-0.000138,0.000263,0.004952,0.023061,0.004389,23.061745,52.67326,74.293793,0,0,-0.171142,0.089536,0.334432,-0.058584,-0.00509,-0.022797,0.089533,0.334481,0,107423,107618,107677,107575 -4.521059,-0.02949,0.002408,-0.982336,-0.006706,-0.007615,-0.00289,0,-0.000138,0.000263,0.004952,0.023061,0.004389,23.061745,54.626244,74.293793,0,0,-0.171142,0.089536,0.334432,-0.058584,-0.00509,-0.022797,0.089533,0.334481,0,107422,107616,107679,107577 -4.52606,-0.029979,0.002896,-0.982092,-0.006706,-0.008679,-0.00289,0,-0.000138,0.000263,0.004952,0.023061,0.004389,25.014729,54.626244,74.293793,0,0,-0.171142,0.089536,0.334432,-0.058584,-0.00509,-0.022797,0.089533,0.334481,0,107420,107618,107677,107579 -4.531061,-0.029979,0.002896,-0.982336,-0.006706,-0.008679,-0.00289,0,-0.000138,0.000263,0.004952,0.023061,0.004389,25.014729,54.626244,74.293793,0,0,-0.171142,0.089536,0.334432,-0.058584,-0.00509,-0.022797,0.089533,0.334481,0,107420,107618,107677,107579 -4.536062,-0.030223,0.002408,-0.982824,-0.005642,-0.008679,-0.00289,0,-0.000138,0.000263,0.004952,0.023061,0.004389,25.014729,52.67326,74.293793,0,0,-0.171142,0.089536,0.334432,-0.058584,-0.00509,-0.022797,0.089533,0.334481,0,107429,107627,107682,107584 -4.541063,-0.030711,0.002652,-0.983312,-0.005642,-0.008679,-0.00289,0,-0.000138,0.000263,0.004952,0.023061,0.004389,25.014729,52.67326,74.293793,0,0,-0.171142,0.089536,0.334432,-0.058584,-0.00509,-0.022797,0.089533,0.334481,0,107429,107627,107682,107584 -4.546064,-0.030711,0.002896,-0.983068,-0.006706,-0.008679,-0.00289,0,0.001645,0.000301,0.002491,0.019761,0.01815,20.498793,48.571953,214.730896,0,0,-0.171458,0.089651,0.334404,-0.058445,-0.000846,-0.019461,0.089533,0.334481,0,107297,107767,107823,107435 -4.551065,-0.030711,0.002896,-0.98258,-0.006706,-0.008679,-0.00289,0,-0.000749,0.000052,0.004125,0.022386,0.008569,23.497255,53.387379,116.946236,0,0,-0.171473,0.089616,0.334369,-0.058617,-0.004875,-0.022333,0.089533,0.334481,0,107387,107668,107727,107540 -4.556067,-0.030467,0.002652,-0.982824,-0.006706,-0.008679,-0.00289,0,-0.000749,0.000052,0.004125,0.022386,0.008569,23.497255,53.387379,116.946236,0,0,-0.171473,0.089616,0.334369,-0.058617,-0.004875,-0.022333,0.089533,0.334481,0,107387,107668,107727,107540 -4.561068,-0.030467,0.002896,-0.982824,-0.006706,-0.008679,-0.00289,0,-0.000322,-0.000615,0.00501,0.022071,0.002069,25.1215,52.81036,50.607319,0,0,-0.171338,0.089573,0.334412,-0.058608,-0.005332,-0.022686,0.089533,0.334481,0,107454,107605,107661,107610 -4.566069,-0.030223,0.002652,-0.983557,-0.006706,-0.008679,-0.00289,0,-0.000322,-0.000615,0.00501,0.022071,0.002069,25.1215,52.81036,50.607319,0,0,-0.171338,0.089573,0.334412,-0.058608,-0.005332,-0.022686,0.089533,0.334481,0,107454,107605,107661,107610 -4.57107,-0.030467,0.002408,-0.983557,-0.006706,-0.008679,-0.00289,0,-0.000322,-0.000615,0.00501,0.022071,0.002069,25.1215,52.81036,50.607319,0,0,-0.171338,0.089573,0.334412,-0.058608,-0.005332,-0.022686,0.089533,0.334481,0,107454,107605,107661,107610 -4.576071,-0.030223,0.002408,-0.983557,-0.005642,-0.008679,-0.00289,0,-0.000322,-0.000615,0.00501,0.022071,0.002069,25.1215,50.857376,50.607319,0,0,-0.171338,0.089573,0.334412,-0.058608,-0.005332,-0.022686,0.089533,0.334481,0,107456,107607,107659,107608 -4.581072,-0.030223,0.002652,-0.983801,-0.006706,-0.008679,-0.00289,0,-0.000322,-0.000615,0.00501,0.022071,0.002069,25.1215,52.81036,50.607319,0,0,-0.171338,0.089573,0.334412,-0.058608,-0.005332,-0.022686,0.089533,0.334481,0,107518,107669,107725,107674 -4.586073,-0.029979,0.002408,-0.983801,-0.005642,-0.008679,-0.00289,0,-0.000322,-0.000615,0.00501,0.022071,0.002069,25.1215,50.857376,50.607319,0,0,-0.171338,0.089573,0.334412,-0.058608,-0.005332,-0.022686,0.089533,0.334481,0,107520,107671,107723,107672 -4.591074,-0.029979,0.002408,-0.983312,-0.005642,-0.008679,-0.00289,0,-0.000351,0.000007,0.005059,0.022418,0.002529,25.21126,51.493149,55.311657,0,0,-0.171258,0.08954,0.334428,-0.058602,-0.00541,-0.022411,0.089533,0.334481,0,107514,107676,107728,107668 -4.596075,-0.030223,0.002896,-0.983557,-0.005642,-0.007615,-0.00289,0,-0.000275,-0.000344,0.005018,0.022206,-0.004197,23.18327,51.105793,-13.336905,0,0,-0.170965,0.089482,0.334477,-0.0586,-0.005293,-0.02255,0.089533,0.334481,0,107586,107605,107661,107734 -4.601076,-0.030223,0.002896,-0.984289,-0.005642,-0.008679,-0.00289,0,-0.000275,-0.000344,0.005018,0.022206,-0.004197,25.136253,51.105793,-13.336905,0,0,-0.170965,0.089482,0.334477,-0.0586,-0.005293,-0.02255,0.089533,0.334481,0,107584,107607,107659,107736 -4.606077,-0.029979,0.003385,-0.983557,-0.005642,-0.008679,-0.00289,0,-0.000275,-0.000344,0.005018,0.022206,-0.004197,25.136253,51.105793,-13.336905,0,0,-0.170965,0.089482,0.334477,-0.0586,-0.005293,-0.02255,0.089533,0.334481,0,107520,107543,107595,107672 -4.611078,-0.030467,0.003141,-0.983068,-0.005642,-0.007615,-0.00289,0,-0.000275,-0.000344,0.005018,0.022206,-0.004197,23.18327,51.105793,-13.336905,0,0,-0.170965,0.089482,0.334477,-0.0586,-0.005293,-0.02255,0.089533,0.334481,0,107522,107541,107597,107670 -4.616079,-0.030467,0.002652,-0.982824,-0.006706,-0.007615,-0.00289,0,-0.000275,-0.000344,0.005018,0.022206,-0.004197,23.18327,53.058777,-13.336905,0,0,-0.170965,0.089482,0.334477,-0.0586,-0.005293,-0.02255,0.089533,0.334481,0,107520,107539,107599,107672 -4.62108,-0.030711,0.002652,-0.983068,-0.006706,-0.007615,-0.00289,0,-0.000275,-0.000344,0.005018,0.022206,-0.004197,23.18327,53.058777,-13.336905,0,0,-0.170965,0.089482,0.334477,-0.0586,-0.005293,-0.02255,0.089533,0.334481,0,107520,107539,107599,107672 -4.626081,-0.030955,0.002652,-0.98258,-0.006706,-0.007615,-0.00289,0,0.000832,0.00056,0.00581,0.023499,0.008511,24.635057,55.430447,116.359261,0,0,-0.171136,0.089535,0.334446,-0.058561,-0.004978,-0.022939,0.089533,0.334481,0,107386,107668,107730,107546 -4.631083,-0.030711,0.00192,-0.98258,-0.006706,-0.007615,-0.00289,0,-0.000157,-0.000139,0.004394,0.022731,0.002306,22.036592,54.0219,53.030403,0,0,-0.171105,0.089565,0.334432,-0.058577,-0.004551,-0.02287,0.089533,0.334481,0,107453,107604,107668,107606 -4.636084,-0.030955,0.001432,-0.983068,-0.006706,-0.007615,-0.00289,0,-0.000157,-0.000139,0.004394,0.022731,0.002306,22.036592,54.0219,53.030403,0,0,-0.171105,0.089565,0.334432,-0.058577,-0.004551,-0.02287,0.089533,0.334481,0,107453,107604,107668,107606 -4.641085,-0.030467,0.001432,-0.983557,-0.006706,-0.007615,-0.00289,0,-0.000157,-0.000139,0.004394,0.022731,0.002306,22.036592,54.0219,53.030403,0,0,-0.171105,0.089565,0.334432,-0.058577,-0.004551,-0.02287,0.089533,0.334481,0,107453,107604,107668,107606 -4.646086,-0.030223,0.001676,-0.983801,-0.006706,-0.007615,-0.00289,0,-0.000157,-0.000139,0.004394,0.022731,0.002306,22.036592,54.0219,53.030403,0,0,-0.171105,0.089565,0.334432,-0.058577,-0.004551,-0.02287,0.089533,0.334481,0,107454,107605,107669,107607 -4.651087,-0.029979,0.001676,-0.983557,-0.006706,-0.007615,-0.00289,0,-0.000157,-0.000139,0.004394,0.022731,0.002306,22.036592,54.0219,53.030403,0,0,-0.171105,0.089565,0.334432,-0.058577,-0.004551,-0.02287,0.089533,0.334481,0,107454,107605,107669,107607 -4.656088,-0.030467,0.001676,-0.983801,-0.006706,-0.007615,-0.00289,0,-0.000157,-0.000139,0.004394,0.022731,0.002306,22.036592,54.0219,53.030403,0,0,-0.171105,0.089565,0.334432,-0.058577,-0.004551,-0.02287,0.089533,0.334481,0,107454,107605,107669,107607 -4.661089,-0.030467,0.00192,-0.983557,-0.006706,-0.007615,-0.00289,0,0.000214,0.000084,0.00488,0.02339,0.005578,22.929636,55.230167,86.422653,0,0,-0.171217,0.089599,0.334425,-0.05854,-0.004666,-0.023306,0.089533,0.334481,0,107419,107638,107702,107575 -4.66609,-0.030223,0.001676,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000214,0.000084,0.00488,0.02339,0.005578,22.929636,55.230167,86.422653,0,0,-0.171217,0.089599,0.334425,-0.05854,-0.004666,-0.023306,0.089533,0.334481,0,107419,107638,107702,107575 -4.671091,-0.030711,0.001676,-0.983312,-0.006706,-0.007615,-0.00289,0,-0.000806,-0.000391,0.004196,0.022631,-0.004436,21.673399,53.837368,-15.776862,0,0,-0.17103,0.089547,0.334451,-0.058545,-0.005001,-0.023022,0.089533,0.334481,0,107525,107537,107601,107676 -4.676092,-0.030711,0.001676,-0.983068,-0.006706,-0.007615,-0.00289,0,-0.000806,-0.000391,0.004196,0.022631,-0.004436,21.673399,53.837368,-15.776862,0,0,-0.17103,0.089547,0.334451,-0.058545,-0.005001,-0.023022,0.089533,0.334481,0,107525,107537,107601,107676 -4.681093,-0.030955,0.00192,-0.982824,-0.006706,-0.007615,-0.00289,0,-0.000806,-0.000391,0.004196,0.022631,-0.004436,21.673399,53.837368,-15.776862,0,0,-0.17103,0.089547,0.334451,-0.058545,-0.005001,-0.023022,0.089533,0.334481,0,107525,107537,107601,107676 -4.686094,-0.030467,0.002164,-0.983312,-0.006706,-0.007615,-0.00289,0,-0.000806,-0.000391,0.004196,0.022631,-0.004436,21.673399,53.837368,-15.776862,0,0,-0.17103,0.089547,0.334451,-0.058545,-0.005001,-0.023022,0.089533,0.334481,0,107525,107537,107601,107676 -4.691095,-0.030711,0.002164,-0.982824,-0.006706,-0.007615,-0.00289,0,-0.000806,-0.000391,0.004196,0.022631,-0.004436,21.673399,53.837368,-15.776862,0,0,-0.17103,0.089547,0.334451,-0.058545,-0.005001,-0.023022,0.089533,0.334481,0,107520,107532,107596,107671 -4.696096,-0.030467,0.002164,-0.982092,-0.006706,-0.007615,-0.00289,0,-0.000806,-0.000391,0.004196,0.022631,-0.004436,21.673399,53.837368,-15.776862,0,0,-0.17103,0.089547,0.334451,-0.058545,-0.005001,-0.023022,0.089533,0.334481,0,107520,107532,107596,107671 -4.701097,-0.030223,0.002408,-0.982092,-0.006706,-0.007615,-0.00289,0,-0.000806,-0.000391,0.004196,0.022631,-0.004436,21.673399,53.837368,-15.776862,0,0,-0.17103,0.089547,0.334451,-0.058545,-0.005001,-0.023022,0.089533,0.334481,0,107520,107532,107596,107671 -4.706099,-0.030223,0.002408,-0.981848,-0.005642,-0.007615,-0.00289,0,0.00124,0.000559,0.00614,0.023546,0.009368,25.240606,53.564583,125.107658,0,0,-0.171198,0.089615,0.334421,-0.058533,-0.0049,-0.022988,0.089533,0.334481,0,107376,107676,107733,107533 -4.7111,-0.030711,0.002164,-0.981604,-0.006706,-0.007615,-0.00289,0,-0.000598,-0.000285,0.004595,0.023093,0.001347,22.406462,54.685474,43.248199,0,0,-0.171093,0.089582,0.33444,-0.058548,-0.005194,-0.023378,0.089533,0.334481,0,107459,107590,107655,107613 -4.716101,-0.030223,0.00192,-0.98258,-0.006706,-0.007615,-0.00289,0,-0.000598,-0.000285,0.004595,0.023093,0.001347,22.406462,54.685474,43.248199,0,0,-0.171093,0.089582,0.33444,-0.058548,-0.005194,-0.023378,0.089533,0.334481,0,107461,107592,107657,107615 -4.721102,-0.030223,0.001432,-0.982092,-0.005642,-0.007615,-0.00289,0,-0.000598,-0.000285,0.004595,0.023093,0.001347,22.406462,52.732491,43.248199,0,0,-0.171093,0.089582,0.33444,-0.058548,-0.005194,-0.023378,0.089533,0.334481,0,107463,107594,107655,107613 -4.726103,-0.029734,0.001676,-0.98258,-0.005642,-0.008679,-0.00289,0,-0.000598,-0.000285,0.004595,0.023093,0.001347,24.359446,52.732491,43.248199,0,0,-0.171093,0.089582,0.33444,-0.058548,-0.005194,-0.023378,0.089533,0.334481,0,107461,107596,107653,107615 -4.731104,-0.02949,0.00192,-0.982336,-0.005642,-0.008679,-0.00289,0,-0.000598,-0.000285,0.004595,0.023093,0.001347,24.359446,52.732491,43.248199,0,0,-0.171093,0.089582,0.33444,-0.058548,-0.005194,-0.023378,0.089533,0.334481,0,107461,107596,107653,107615 -4.736105,-0.02949,0.001676,-0.982824,-0.005642,-0.007615,-0.00289,0,-0.000598,-0.000285,0.004595,0.023093,0.001347,22.406462,52.732491,43.248199,0,0,-0.171093,0.089582,0.33444,-0.058548,-0.005194,-0.023378,0.089533,0.334481,0,107525,107656,107717,107675 -4.741106,-0.02949,0.00192,-0.983068,-0.005642,-0.007615,-0.00289,0,0.000929,0.000583,0.005726,0.023701,0.010998,24.482285,53.849144,141.735474,0,0,-0.171274,0.089633,0.334405,-0.058533,-0.004797,-0.023119,0.089533,0.334481,0,107423,107756,107815,107580 -4.746107,-0.029246,0.002164,-0.983312,-0.006706,-0.008679,-0.00289,0,-0.000862,-0.000438,0.004126,0.022341,0.000499,23.498096,53.305527,34.586876,0,0,-0.171122,0.089557,0.334438,-0.05855,-0.004988,-0.022779,0.089533,0.334481,0,107532,107648,107708,107686 -4.751108,-0.029246,0.002408,-0.983557,-0.006706,-0.007615,-0.00289,0,0.000145,0.000034,0.005171,0.022588,0.001457,23.463337,53.75869,44.361294,0,0,-0.171091,0.089545,0.334447,-0.058582,-0.005026,-0.022553,0.089533,0.334481,0,107522,107658,107718,107676 -4.756109,-0.029246,0.002408,-0.983557,-0.006706,-0.007615,-0.00289,0,0.000145,0.000034,0.005171,0.022588,0.001457,23.463337,53.75869,44.361294,0,0,-0.171091,0.089545,0.334447,-0.058582,-0.005026,-0.022553,0.089533,0.334481,0,107522,107658,107718,107676 -4.76111,-0.029734,0.002408,-0.983312,-0.005642,-0.007615,-0.00289,0,0.000145,0.000034,0.005171,0.022588,0.001457,23.463337,51.805706,44.361294,0,0,-0.171091,0.089545,0.334447,-0.058582,-0.005026,-0.022553,0.089533,0.334481,0,107531,107667,107723,107681 -4.766111,-0.029734,0.002652,-0.983068,-0.005642,-0.007615,-0.00289,0,0.000145,0.000034,0.005171,0.022588,0.001457,23.463337,51.805706,44.361294,0,0,-0.171091,0.089545,0.334447,-0.058582,-0.005026,-0.022553,0.089533,0.334481,0,107531,107667,107723,107681 -4.771112,-0.029246,0.002164,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000145,0.000034,0.005171,0.022588,0.001457,23.463337,53.75869,44.361294,0,0,-0.171091,0.089545,0.334447,-0.058582,-0.005026,-0.022553,0.089533,0.334481,0,107529,107665,107725,107683 -4.776114,-0.02949,0.001676,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000145,0.000034,0.005171,0.022588,0.001457,23.463337,53.75869,44.361294,0,0,-0.171091,0.089545,0.334447,-0.058582,-0.005026,-0.022553,0.089533,0.334481,0,107529,107665,107725,107683 -4.781115,-0.030223,0.001432,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000145,0.000034,0.005171,0.022588,0.001457,23.463337,53.75869,44.361294,0,0,-0.171091,0.089545,0.334447,-0.058582,-0.005026,-0.022553,0.089533,0.334481,0,108617,108753,108813,108771 -4.786116,-0.029979,0.001676,-0.983312,-0.006706,-0.007615,-0.00289,0,0.001408,0.0013,0.006196,0.024047,0.019155,25.34483,56.437271,224.985657,0,0,-0.171446,0.08965,0.334352,-0.058588,-0.004789,-0.022748,0.089533,0.334481,0,108432,108932,108995,108595 -4.791117,-0.029734,0.00192,-0.983068,-0.006706,-0.007615,-0.00289,0,-0.001996,-0.001756,0.003146,0.020679,-0.005278,19.747427,50.256184,-24.36961,0,0,-0.171165,0.089542,0.334446,-0.058581,-0.005142,-0.022435,0.089533,0.334481,0,108693,108684,108745,108833 -4.796118,-0.029734,0.00192,-0.983068,-0.006706,-0.007615,-0.00289,0,0.000663,0.000652,0.005871,0.023515,0.003267,24.747391,55.460426,62.836617,0,0,-0.171155,0.089535,0.334442,-0.058562,-0.005207,-0.022863,0.089533,0.334481,0,108595,108771,108832,108756 -4.801119,-0.029734,0.00192,-0.983801,-0.006706,-0.007615,-0.00289,0,-0.000882,-0.000604,0.004652,0.021982,-0.003892,22.510675,52.646004,-10.220482,0,0,-0.171,0.089489,0.334469,-0.058576,-0.005534,-0.022586,0.089533,0.334481,0,113089,113113,113173,113239 -4.80612,-0.029979,0.00192,-0.984289,-0.006706,-0.007615,-0.00289,0,-0.000882,-0.000604,0.004652,0.021982,-0.003892,22.510675,52.646004,-10.220482,0,0,-0.171,0.089489,0.334469,-0.058576,-0.005534,-0.022586,0.089533,0.334481,0,113089,113113,113173,113239 -4.811121,-0.029734,0.002408,-0.983557,-0.006706,-0.007615,-0.00289,0,-0.000882,-0.000604,0.004652,0.021982,-0.003892,22.510675,52.646004,-10.220482,0,0,-0.171,0.089489,0.334469,-0.058576,-0.005534,-0.022586,0.089533,0.334481,0,113089,113113,113173,113239 -4.816122,-0.029734,0.002896,-0.983557,-0.006706,-0.007615,-0.00289,0,-0.000882,-0.000604,0.004652,0.021982,-0.003892,22.510675,52.646004,-10.220482,0,0,-0.171,0.089489,0.334469,-0.058576,-0.005534,-0.022586,0.089533,0.334481,0,113089,113113,113173,113239 -4.821123,-0.029734,0.002652,-0.983312,-0.006706,-0.007615,-0.00289,0,-0.000882,-0.000604,0.004652,0.021982,-0.003892,22.510675,52.646004,-10.220482,0,0,-0.171,0.089489,0.334469,-0.058576,-0.005534,-0.022586,0.089533,0.334481,0,113089,113113,113173,113239 -4.826124,-0.029979,0.002408,-0.983312,-0.006706,-0.007615,-0.00289,0,-0.000882,-0.000604,0.004652,0.021982,-0.003892,22.510675,52.646004,-10.220482,0,0,-0.171,0.089489,0.334469,-0.058576,-0.005534,-0.022586,0.089533,0.334481,0,115183,115207,115267,115333 -4.831125,-0.030223,0.002408,-0.983312,-0.006706,-0.007615,-0.00289,0,0.000596,0.000427,0.005739,0.023174,0.006648,24.506088,54.834915,97.340195,0,0,-0.171216,0.089549,0.334423,-0.058597,-0.005143,-0.022747,0.089533,0.334481,0,115071,115315,115375,115230 -4.836126,-0.030223,0.002408,-0.983068,-0.006706,-0.007615,-0.00289,0,0.000596,0.000427,0.005739,0.023174,0.006648,24.506088,54.834915,97.340195,0,0,-0.171216,0.089549,0.334423,-0.058597,-0.005143,-0.022747,0.089533,0.334481,0,115071,115315,115375,115230 -4.841127,-0.030223,0.002652,-0.983557,-0.006706,-0.007615,-0.00289,0,-0.000523,-0.000467,0.004477,0.02226,0.002637,22.188906,53.156162,56.406334,0,0,-0.171179,0.089527,0.334446,-0.05859,-0.004999,-0.022726,0.089533,0.334481,0,115116,115273,115335,115266 -4.846128,-0.030223,0.002408,-0.983557,-0.006706,-0.007615,-0.00289,0,-0.000523,-0.000467,0.004477,0.02226,0.002637,22.188906,53.156162,56.406334,0,0,-0.171179,0.089527,0.334446,-0.05859,-0.004999,-0.022726,0.089533,0.334481,0,115612,115769,115831,115762 -4.85113,-0.030223,0.002896,-0.983068,-0.006706,-0.007615,-0.00289,0,-0.000523,-0.000467,0.004477,0.02226,0.002637,22.188906,53.156162,56.406334,0,0,-0.171179,0.089527,0.334446,-0.05859,-0.004999,-0.022726,0.089533,0.334481,0,115612,115769,115831,115762 -4.856131,-0.030467,0.002652,-0.982092,-0.006706,-0.007615,-0.00289,0,-0.000523,-0.000467,0.004477,0.02226,0.002637,22.188906,53.156162,56.406334,0,0,-0.171179,0.089527,0.334446,-0.05859,-0.004999,-0.022726,0.089533,0.334481,0,115612,115769,115831,115762 -4.861132,-0.030467,0.003385,-0.982336,-0.006706,-0.007615,-0.00289,0,-0.000523,-0.000467,0.004477,0.02226,0.002637,22.188906,53.156162,56.406334,0,0,-0.171179,0.089527,0.334446,-0.05859,-0.004999,-0.022726,0.089533,0.334481,0,115612,115769,115831,115762 -4.866133,-0.030711,0.003141,-0.982092,-0.006706,-0.007615,-0.00289,0,-0.000523,-0.000467,0.004477,0.02226,0.002637,22.188906,53.156162,56.406334,0,0,-0.171179,0.089527,0.334446,-0.05859,-0.004999,-0.022726,0.089533,0.334481,0,115612,115769,115831,115762 -4.871134,-0.030711,0.002652,-0.982336,-0.006706,-0.007615,-0.00289,0,-0.000523,-0.000467,0.004477,0.02226,0.002637,22.188906,53.156162,56.406334,0,0,-0.171179,0.089527,0.334446,-0.05859,-0.004999,-0.022726,0.089533,0.334481,0,115721,115878,115940,115871 -4.876135,-0.030955,0.002164,-0.982336,-0.006706,-0.007615,-0.00289,0,0.000558,0.000553,0.005858,0.022902,0.007494,24.723827,54.334675,105.982864,0,0,-0.171257,0.089554,0.334418,-0.058587,-0.0053,-0.022349,0.089533,0.334481,0,115667,115929,115988,115826 -4.881136,-0.031199,0.002164,-0.981604,-0.006706,-0.007615,-0.00289,0,-0.00002,-0.000155,0.005558,0.022478,0.006512,24.172529,53.557907,95.956955,0,0,-0.171314,0.089593,0.334409,-0.058583,-0.005578,-0.022633,0.089533,0.334481,0,115679,115919,115978,115834 -4.886137,-0.030955,0.00192,-0.981604,-0.006706,-0.007615,-0.00289,0,-0.00002,-0.000155,0.005558,0.022478,0.006512,24.172529,53.557907,95.956955,0,0,-0.171314,0.089593,0.334409,-0.058583,-0.005578,-0.022633,0.089533,0.334481,0,115679,115919,115978,115834 -4.891138,-0.030711,0.002408,-0.982336,-0.006706,-0.007615,-0.00289,0,-0.00002,-0.000155,0.005558,0.022478,0.006512,24.172529,53.557907,95.956955,0,0,-0.171314,0.089593,0.334409,-0.058583,-0.005578,-0.022633,0.089533,0.334481,0,116992,117232,117291,117147 -4.896139,-0.030467,0.002164,-0.982092,-0.006706,-0.007615,-0.00289,0,-0.00002,-0.000155,0.005558,0.022478,0.006512,24.172529,53.557907,95.956955,0,0,-0.171314,0.089593,0.334409,-0.058583,-0.005578,-0.022633,0.089533,0.334481,0,116992,117232,117291,117147 -4.90114,-0.030467,0.002164,-0.983312,-0.006706,-0.007615,-0.00289,0,-0.00002,-0.000155,0.005558,0.022478,0.006512,24.172529,53.557907,95.956955,0,0,-0.171314,0.089593,0.334409,-0.058583,-0.005578,-0.022633,0.089533,0.334481,0,116992,117232,117291,117147 -4.906141,-0.030955,0.00192,-0.983801,-0.006706,-0.007615,-0.00289,0,-0.00002,-0.000155,0.005558,0.022478,0.006512,24.172529,53.557907,95.956955,0,0,-0.171314,0.089593,0.334409,-0.058583,-0.005578,-0.022633,0.089533,0.334481,0,116992,117232,117291,117147 -4.911142,-0.030955,0.001676,-0.982824,-0.006706,-0.007615,-0.00289,0,-0.000616,-0.000345,0.004187,0.022629,-0.000633,21.657187,53.833618,23.033804,0,0,-0.171175,0.089547,0.334438,-0.058586,-0.004803,-0.022974,0.089533,0.334481,0,117881,117970,118035,118032 -4.916143,-0.030223,0.001187,-0.98258,-0.006706,-0.007615,-0.00289,0,0.000014,-0.000071,0.005118,0.023091,-0.001701,23.366096,54.681622,12.131695,0,0,-0.171003,0.089518,0.334466,-0.058562,-0.005104,-0.023161,0.089533,0.334481,0,117889,117960,118023,118045 -4.921144,-0.029979,0.001187,-0.982824,-0.006706,-0.008679,-0.00289,0,0.000014,-0.000071,0.005118,0.023091,-0.001701,25.319078,54.681622,12.131695,0,0,-0.171003,0.089518,0.334466,-0.058562,-0.005104,-0.023161,0.089533,0.334481,0,117887,117962,118021,118047 -4.926146,-0.030467,0.001676,-0.983557,-0.006706,-0.008679,-0.00289,0,0.000014,-0.000071,0.005118,0.023091,-0.001701,25.319078,54.681622,12.131695,0,0,-0.171003,0.089518,0.334466,-0.058562,-0.005104,-0.023161,0.089533,0.334481,0,117887,117962,118021,118047 -4.931147,-0.030711,0.001432,-0.984777,-0.006706,-0.008679,-0.00289,0,0.000014,-0.000071,0.005118,0.023091,-0.001701,25.319078,54.681622,12.131695,0,0,-0.171003,0.089518,0.334466,-0.058562,-0.005104,-0.023161,0.089533,0.334481,0,117887,117962,118021,118047 -4.936148,-0.030467,0.00192,-0.984045,-0.006706,-0.008679,-0.00289,0,0.000014,-0.000071,0.005118,0.023091,-0.001701,25.319078,54.681622,12.131695,0,0,-0.171003,0.089518,0.334466,-0.058562,-0.005104,-0.023161,0.089533,0.334481,0,118107,118182,118241,118267 -4.941149,-0.030223,0.002408,-0.983557,-0.006706,-0.008679,-0.00289,0,0.000014,-0.000071,0.005118,0.023091,-0.001701,25.319078,54.681622,12.131695,0,0,-0.171003,0.089518,0.334466,-0.058562,-0.005104,-0.023161,0.089533,0.334481,0,118107,118182,118241,118267 -4.94615,-0.029979,0.002164,-0.983557,-0.006706,-0.008679,-0.00289,0,0.000014,-0.000071,0.005118,0.023091,-0.001701,25.319078,54.681622,12.131695,0,0,-0.171003,0.089518,0.334466,-0.058562,-0.005104,-0.023161,0.089533,0.334481,0,118107,118182,118241,118267 -4.951151,-0.029246,0.002164,-0.983557,-0.006706,-0.008679,-0.00289,0,0.000569,0.000245,0.005432,0.022799,0.005907,25.895714,54.146061,89.781197,0,0,-0.171106,0.089559,0.33445,-0.058543,-0.004864,-0.022554,0.089533,0.334481,0,118030,118261,118318,118190 -4.956152,-0.029002,0.002652,-0.983801,-0.006706,-0.007615,-0.00289,0,0.000528,0.000237,0.00102,0.019846,0.011706,15.845316,48.726826,148.966217,0,0,-0.171451,0.089717,0.33438,-0.058419,-0.000492,-0.019609,0.089533,0.334481,0,118484,118814,118879,118613 -4.961153,-0.029002,0.002408,-0.983801,-0.006706,-0.007615,-0.00289,0,-0.002157,-0.000794,0.002993,0.022345,-0.007612,19.467171,53.313316,-48.187401,0,0,-0.171119,0.089575,0.334431,-0.058552,-0.005151,-0.023139,0.089533,0.334481,0,118673,118615,118683,118818 -4.966154,-0.029979,0.003873,-0.98258,-0.006706,-0.007615,-0.001826,0,-0.002157,-0.000794,0.002993,0.022345,-0.007612,19.467171,53.313316,-59.048672,0,0,-0.171119,0.089575,0.334431,-0.058552,-0.005151,-0.023139,0.089533,0.334481,0,118684,118605,118672,118829 -4.971155,-0.029734,0.002408,-0.983068,-0.005642,-0.008679,-0.001826,0,-0.002157,-0.000794,0.002993,0.022345,-0.007612,21.420155,51.360332,-59.048672,0,0,-0.171119,0.089575,0.334431,-0.058552,-0.005151,-0.023139,0.089533,0.334481,0,118684,118609,118668,118829 -4.976156,-0.029734,0.002408,-0.982092,-0.006706,-0.007615,-0.001826,0,-0.002157,-0.000794,0.002993,0.022345,-0.007612,19.467171,53.313316,-59.048672,0,0,-0.171119,0.089575,0.334431,-0.058552,-0.005151,-0.023139,0.089533,0.334481,0,118684,118605,118672,118829 -4.981157,-0.029979,0.003141,-0.98258,-0.006706,-0.008679,-0.00289,0,-0.002157,-0.000794,0.002993,0.022345,-0.007612,21.420155,53.313316,-48.187401,0,0,-0.171119,0.089575,0.334431,-0.058552,-0.005151,-0.023139,0.089533,0.334481,0,119339,119285,119349,119488 -4.986158,-0.029734,0.001432,-0.984045,-0.006706,-0.008679,-0.003954,0,-0.002157,-0.000794,0.002993,0.022345,-0.007612,21.420155,53.313316,-37.32613,0,0,-0.171119,0.089575,0.334431,-0.058552,-0.005151,-0.023139,0.089533,0.334481,0,119328,119296,119360,119478 -4.991159,-0.030955,0.004605,-0.983068,-0.006706,-0.007615,-0.006083,0,0.000513,0.000072,0.005277,0.023308,-0.000211,23.657558,55.080093,59.924477,0,0,-0.171054,0.089557,0.334446,-0.058533,-0.004764,-0.023236,0.089533,0.334481,0,119227,119394,119457,119384 -4.996161,-0.028025,0.002408,-0.983801,-0.006706,-0.009743,-0.006083,0,-0.000014,0.000047,0.004717,0.023523,0.004135,26.535301,55.475468,104.279709,0,0,-0.171127,0.089581,0.334436,-0.05853,-0.00473,-0.023476,0.089533,0.334481,0,119179,119441,119499,119343 -5.001162,-0.030223,0.001432,-0.982336,-0.006706,-0.007615,-0.003954,0,0.001054,0.000619,0.005686,0.023945,0.014394,24.409218,56.248547,187.264343,0,0,-0.171369,0.089657,0.33439,-0.058534,-0.004632,-0.023326,0.089533,0.334481,0,120085,120508,120572,120246 -5.006163,-0.029246,0.002896,-0.982824,-0.006706,-0.008679,-0.00289,0,0.001054,0.000619,0.005686,0.023945,0.014394,26.362202,56.248547,176.403061,0,0,-0.171369,0.089657,0.33439,-0.058534,-0.004632,-0.023326,0.089533,0.334481,0,120093,120499,120559,120259 -5.011164,-0.031443,0.000455,-0.983312,-0.006706,-0.008679,-0.000762,0,0.001054,0.000619,0.005686,0.023945,0.014394,26.362202,56.248547,154.680511,0,0,-0.171369,0.089657,0.33439,-0.058534,-0.004632,-0.023326,0.089533,0.334481,0,120115,120477,120537,120280 -5.016165,-0.028514,0.004361,-0.983312,-0.006706,-0.007615,-0.000762,0,0.001054,0.000619,0.005686,0.023945,0.014394,24.409218,56.248547,154.680511,0,0,-0.171369,0.089657,0.33439,-0.058534,-0.004632,-0.023326,0.089533,0.334481,0,120117,120475,120539,120278 -5.021166,-0.030223,0.002164,-0.983801,-0.006706,-0.007615,-0.00289,0,0.001054,0.000619,0.005686,0.023945,0.014394,24.409218,56.248547,176.403061,0,0,-0.171369,0.089657,0.33439,-0.058534,-0.004632,-0.023326,0.089533,0.334481,0,121008,121410,121474,121170 -5.026167,-0.029002,0.004361,-0.982824,-0.006706,-0.007615,-0.003954,0,0.001054,0.000619,0.005686,0.023945,0.014394,24.409218,56.248547,187.264343,0,0,-0.171369,0.089657,0.33439,-0.058534,-0.004632,-0.023326,0.089533,0.334481,0,120998,121421,121485,121159 -5.031168,-0.029734,0.002408,-0.983068,-0.006706,-0.007615,-0.005019,0,0.001054,0.000619,0.005686,0.023945,0.014394,24.409218,56.248547,198.12561,0,0,-0.171369,0.089657,0.33439,-0.058534,-0.004632,-0.023326,0.089533,0.334481,0,120987,121432,121495,121148 -5.036169,-0.029979,0.002164,-0.981848,-0.006706,-0.007615,-0.005019,0,-0.000803,-0.000383,0.003849,0.023534,0.000692,21.036312,55.495525,58.282188,0,0,-0.171137,0.089564,0.334425,-0.058526,-0.004652,-0.023917,0.089533,0.334481,0,121131,121289,121358,121284 -5.04117,-0.029979,0.004117,-0.983312,-0.006706,-0.008679,-0.00289,0,0.000216,0.000151,0.00513,0.023168,0.003162,25.34186,54.823647,61.764637,0,0,-0.171137,0.089559,0.334424,-0.058553,-0.004914,-0.023017,0.089533,0.334481,0,121124,121298,121357,121284 -5.046171,-0.031443,0.000699,-0.983068,-0.006706,-0.007615,-0.001826,0,0.000216,0.000151,0.00513,0.023168,0.003162,23.388876,54.823647,50.903362,0,0,-0.171137,0.089559,0.334424,-0.058553,-0.004914,-0.023017,0.089533,0.334481,0,122341,122490,122553,122498 -5.051172,-0.028514,0.004117,-0.982824,-0.006706,-0.007615,0.000303,0,0.000216,0.000151,0.00513,0.023168,0.003162,23.388876,54.823647,29.180815,0,0,-0.171137,0.089559,0.334424,-0.058553,-0.004914,-0.023017,0.089533,0.334481,0,122363,122468,122531,122520 -5.056173,-0.03242,0.002164,-0.983312,-0.005642,-0.008679,-0.001826,0,0.000216,0.000151,0.00513,0.023168,0.003162,25.34186,52.870663,50.903362,0,0,-0.171137,0.089559,0.334424,-0.058553,-0.004914,-0.023017,0.089533,0.334481,0,122341,122494,122549,122498 -5.061174,-0.029734,0.003873,-0.983801,-0.006706,-0.00655,-0.00289,0,0.000216,0.000151,0.00513,0.023168,0.003162,21.435892,54.823647,61.764637,0,0,-0.171137,0.089559,0.334424,-0.058553,-0.004914,-0.023017,0.089533,0.334481,0,122332,122499,122566,122485 -5.066175,-0.029979,0.003873,-0.985021,-0.006706,-0.008679,-0.005019,0,0.000216,0.000151,0.00513,0.023168,0.003162,25.34186,54.823647,83.487183,0,0,-0.171137,0.089559,0.334424,-0.058553,-0.004914,-0.023017,0.089533,0.334481,0,122840,123058,123116,123000 -5.071177,-0.031443,0.001432,-0.983801,-0.006706,-0.007615,-0.00289,0,-0.000263,-0.000198,0.004831,0.022548,0.002069,22.838564,53.685863,50.609726,0,0,-0.171103,0.089532,0.334445,-0.058571,-0.005094,-0.022746,0.089533,0.334481,0,122876,123023,123085,123029 -5.076178,-0.029979,0.002408,-0.984533,-0.005642,-0.007615,-0.001826,0,0.000445,0.000689,0.005258,0.023035,0.011026,23.622461,52.625805,131.163574,0,0,-0.171282,0.089558,0.3344,-0.058608,-0.004812,-0.022346,0.089533,0.334481,0,122796,123106,123164,122949 -5.081179,-0.031199,0.000943,-0.983557,-0.006706,-0.008679,-0.000762,0,0.000445,0.000689,0.005258,0.023035,0.011026,25.575445,54.578789,120.302299,0,0,-0.171282,0.089558,0.3344,-0.058608,-0.004812,-0.022346,0.089533,0.334481,0,122803,123095,123153,122963 -5.08618,-0.029246,0.002896,-0.984533,-0.006706,-0.007615,-0.000762,0,0.000445,0.000689,0.005258,0.023035,0.011026,23.622461,54.578789,120.302299,0,0,-0.171282,0.089558,0.3344,-0.058608,-0.004812,-0.022346,0.089533,0.334481,0,122805,123093,123155,122961 -5.091181,-0.029979,0.002164,-0.984777,-0.005642,-0.007615,-0.001826,0,0.000445,0.000689,0.005258,0.023035,0.011026,23.622461,52.625805,131.163574,0,0,-0.171282,0.089558,0.3344,-0.058608,-0.004812,-0.022346,0.089533,0.334481,0,123527,123837,123895,123680 -5.096182,-0.029246,0.003141,-0.984533,-0.006706,-0.008679,-0.003954,0,0.000445,0.000689,0.005258,0.023035,0.011026,25.575445,54.578789,152.886124,0,0,-0.171282,0.089558,0.3344,-0.058608,-0.004812,-0.022346,0.089533,0.334481,0,123501,123858,123916,123662 -5.101183,-0.030711,0.000943,-0.983557,-0.005642,-0.007615,-0.003954,0,0.000445,0.000689,0.005258,0.023035,0.011026,23.622461,52.625805,152.886124,0,0,-0.171282,0.089558,0.3344,-0.058608,-0.004812,-0.022346,0.089533,0.334481,0,123505,123858,123916,123658 -5.106184,-0.029002,0.001676,-0.982092,-0.006706,-0.007615,-0.00289,0,-0.001312,-0.001235,0.003715,0.020853,-0.006648,20.791046,50.575264,-38.354084,0,0,-0.171026,0.089474,0.334471,-0.058622,-0.005027,-0.022088,0.089533,0.334481,0,123701,123666,123726,123844 -5.111185,-0.029734,-0.000521,-0.98258,-0.005642,-0.008679,-0.001826,0,0.000687,0.000314,0.001547,0.019377,0.003137,18.765196,45.913193,50.645809,0,0,-0.171093,0.089522,0.334499,-0.058455,-0.00086,-0.019063,0.089533,0.334481,0,123838,123977,124031,123968 -5.116186,-0.029002,0.002164,-0.983557,-0.006706,-0.007615,-0.000762,0,0.000687,0.000314,0.001547,0.019377,0.003137,16.812212,47.866177,39.784538,0,0,-0.171093,0.089522,0.334499,-0.058455,-0.00086,-0.019063,0.089533,0.334481,0,123849,123962,124024,123978 -5.121187,-0.029734,0.002164,-0.983801,-0.005642,-0.008679,-0.000762,0,0.002437,0.002169,0.007222,0.025033,0.033823,29.180805,56.29311,352.960449,0,0,-0.171757,0.089715,0.334334,-0.058562,-0.004785,-0.022864,0.089533,0.334481,0,123515,124279,124334,123686 -5.126188,-0.030955,0.002164,-0.983801,-0.006706,-0.007615,-0.000762,0,0.002437,0.002169,0.007222,0.025033,0.033823,27.227821,58.246094,352.960449,0,0,-0.171757,0.089715,0.334334,-0.058562,-0.004785,-0.022864,0.089533,0.334481,0,123515,124275,124337,123686 -5.131189,-0.031199,0.003629,-0.984045,-0.006706,-0.008679,-0.001826,0,0.002437,0.002169,0.007222,0.025033,0.033823,29.180805,58.246094,363.821747,0,0,-0.171757,0.089715,0.334334,-0.058562,-0.004785,-0.022864,0.089533,0.334481,0,123509,124295,124353,123684 -5.13619,-0.030711,0.001432,-0.983312,-0.006706,-0.007615,-0.00289,0,0.002437,0.002169,0.007222,0.025033,0.033823,27.227821,58.246094,374.683014,0,0,-0.171757,0.089715,0.334334,-0.058562,-0.004785,-0.022864,0.089533,0.334481,0,123500,124304,124366,123671 -5.141191,-0.02949,0.002652,-0.983557,-0.005642,-0.007615,-0.00289,0,0.002437,0.002169,0.007222,0.025033,0.033823,27.227821,56.29311,374.683014,0,0,-0.171757,0.089715,0.334334,-0.058562,-0.004785,-0.022864,0.089533,0.334481,0,123502,124306,124364,123669 -5.146193,-0.029979,0.001432,-0.982092,-0.006706,-0.008679,-0.001826,0,0.002437,0.002169,0.007222,0.025033,0.033823,29.180805,58.246094,363.821747,0,0,-0.171757,0.089715,0.334334,-0.058562,-0.004785,-0.022864,0.089533,0.334481,0,123509,124295,124353,123684 -5.151194,-0.02949,0.002408,-0.98258,-0.005642,-0.007615,-0.001826,0,-0.00262,-0.001812,0.002426,0.020663,-0.012982,18.425339,48.273617,-113.852333,0,0,-0.170935,0.089463,0.334484,-0.058613,-0.005046,-0.022475,0.089533,0.334481,0,124008,123817,123876,124141 -5.156195,-0.031443,0.001676,-0.982092,-0.006706,-0.007615,-0.001826,0,0.000323,0.000224,0.005602,0.02301,-0.008343,24.25453,54.532623,-66.51416,0,0,-0.17076,0.089418,0.334514,-0.058595,-0.00528,-0.022785,0.089533,0.334481,0,124097,124013,124073,124255 -5.161196,-0.02949,0.002896,-0.98258,-0.006706,-0.007615,-0.00289,0,0.000323,0.000224,0.005602,0.02301,-0.008343,24.25453,54.532623,-55.652889,0,0,-0.17076,0.089418,0.334514,-0.058595,-0.00528,-0.022785,0.089533,0.334481,0,124086,124024,124084,124244 -5.166197,-0.030955,0.002164,-0.983801,-0.005642,-0.007615,-0.00289,0,0.000323,0.000224,0.005602,0.02301,-0.008343,24.25453,52.579639,-55.652889,0,0,-0.17076,0.089418,0.334514,-0.058595,-0.00528,-0.022785,0.089533,0.334481,0,124088,124026,124082,124242 -5.171198,-0.029979,0.001432,-0.983068,-0.006706,-0.007615,-0.00289,0,0.000323,0.000224,0.005602,0.02301,-0.008343,24.25453,54.532623,-55.652889,0,0,-0.17076,0.089418,0.334514,-0.058595,-0.00528,-0.022785,0.089533,0.334481,0,124086,124024,124084,124244 -5.176199,-0.029734,0.001676,-0.983312,-0.005642,-0.007615,-0.001826,0,0.000323,0.000224,0.005602,0.02301,-0.008343,24.25453,52.579639,-66.51416,0,0,-0.17076,0.089418,0.334514,-0.058595,-0.00528,-0.022785,0.089533,0.334481,0,124051,123967,124023,124205 -5.1812,-0.030467,0.000943,-0.983312,-0.006706,-0.007615,-0.000762,0,0.000323,0.000224,0.005602,0.02301,-0.008343,24.25453,54.532623,-77.375435,0,0,-0.17076,0.089418,0.334514,-0.058595,-0.00528,-0.022785,0.089533,0.334481,0,124060,123954,124014,124218 -5.186201,-0.02949,0.002408,-0.983557,-0.006706,-0.007615,-0.001826,0,0.000323,0.000224,0.005602,0.02301,-0.008343,24.25453,54.532623,-66.51416,0,0,-0.17076,0.089418,0.334514,-0.058595,-0.00528,-0.022785,0.089533,0.334481,0,124049,123965,124025,124207 -5.191202,-0.029246,0.001676,-0.983557,-0.006706,-0.007615,-0.001826,0,0.000305,0.000079,0.005192,0.022798,0.004114,23.501451,54.144466,60.620621,0,0,-0.171023,0.089509,0.33448,-0.058556,-0.004887,-0.02272,0.089533,0.334481,0,123923,124091,124153,124079 -5.196203,-0.029246,0.002652,-0.984289,-0.006706,-0.007615,-0.00289,0,-0.000768,-0.00026,0.004328,0.022596,-0.007519,21.916937,53.773796,-47.2407,0,0,-0.170836,0.089462,0.334497,-0.058562,-0.005096,-0.022857,0.089533,0.334481,0,124033,123982,124046,124184 -5.201204,-0.029734,0.001432,-0.983312,-0.006706,-0.007615,-0.001826,0,-0.000768,-0.00026,0.004328,0.022596,-0.007519,21.916937,53.773796,-58.101974,0,0,-0.170836,0.089462,0.334497,-0.058562,-0.005096,-0.022857,0.089533,0.334481,0,124317,124245,124308,124468 -5.206205,-0.029979,0.001676,-0.983068,-0.006706,-0.007615,-0.00289,0,-0.000768,-0.00026,0.004328,0.022596,-0.007519,21.916937,53.773796,-47.2407,0,0,-0.170836,0.089462,0.334497,-0.058562,-0.005096,-0.022857,0.089533,0.334481,0,124306,124255,124319,124457 -5.211206,-0.029979,0.001676,-0.982336,-0.006706,-0.007615,-0.000762,0,-0.000768,-0.00026,0.004328,0.022596,-0.007519,21.916937,53.773796,-68.963249,0,0,-0.170836,0.089462,0.334497,-0.058562,-0.005096,-0.022857,0.089533,0.334481,0,124328,124234,124297,124479 -5.216208,-0.02949,0.001432,-0.983068,-0.006706,-0.007615,-0.000762,0,-0.000768,-0.00026,0.004328,0.022596,-0.007519,21.916937,53.773796,-68.963249,0,0,-0.170836,0.089462,0.334497,-0.058562,-0.005096,-0.022857,0.089533,0.334481,0,124328,124234,124297,124479 -5.221209,-0.029002,0.00192,-0.982824,-0.006706,-0.007615,-0.001826,0,-0.000768,-0.00026,0.004328,0.022596,-0.007519,21.916937,53.773796,-58.101974,0,0,-0.170836,0.089462,0.334497,-0.058562,-0.005096,-0.022857,0.089533,0.334481,0,124824,124752,124815,124975 -5.22621,-0.029734,0.001432,-0.983801,-0.006706,-0.007615,-0.00289,0,0.000541,0.00011,0.005185,0.022547,-0.001698,23.489256,53.683628,12.170769,0,0,-0.170834,0.089481,0.334496,-0.058569,-0.004644,-0.022437,0.089533,0.334481,0,124752,124823,124884,124907 -5.231211,-0.02949,0.00192,-0.983312,-0.006706,-0.007615,-0.003954,0,-0.000198,-0.00008,0.004601,0.022986,-0.003602,22.417988,54.488422,3.600104,0,0,-0.170759,0.08948,0.334504,-0.058543,-0.004799,-0.023065,0.089533,0.334481,0,124761,124813,124877,124915 -5.236212,-0.029979,0.001676,-0.983312,-0.006706,-0.007615,-0.003954,0,-0.000198,-0.00008,0.004601,0.022986,-0.003602,22.417988,54.488422,3.600104,0,0,-0.170759,0.08948,0.334504,-0.058543,-0.004799,-0.023065,0.089533,0.334481,0,124761,124813,124877,124915 -5.241213,-0.029979,0.002652,-0.983312,-0.006706,-0.007615,-0.003954,0,-0.000198,-0.00008,0.004601,0.022986,-0.003602,22.417988,54.488422,3.600104,0,0,-0.170759,0.08948,0.334504,-0.058543,-0.004799,-0.023065,0.089533,0.334481,0,125085,125137,125201,125239 -5.246214,-0.030711,0.00192,-0.981848,-0.006706,-0.007615,-0.00289,0,-0.000198,-0.00008,0.004601,0.022986,-0.003602,22.417988,54.488422,-7.261167,0,0,-0.170759,0.08948,0.334504,-0.058543,-0.004799,-0.023065,0.089533,0.334481,0,125096,125126,125190,125250 -5.251215,-0.030467,0.001432,-0.981604,-0.006706,-0.007615,-0.00289,0,-0.000198,-0.00008,0.004601,0.022986,-0.003602,22.417988,54.488422,-7.261167,0,0,-0.170759,0.08948,0.334504,-0.058543,-0.004799,-0.023065,0.089533,0.334481,0,125096,125126,125190,125250 -5.256216,-0.029734,0.001432,-0.981848,-0.006706,-0.007615,-0.001826,0,-0.000198,-0.00008,0.004601,0.022986,-0.003602,22.417988,54.488422,-18.12244,0,0,-0.170759,0.08948,0.334504,-0.058543,-0.004799,-0.023065,0.089533,0.334481,0,125107,125115,125179,125261 -5.261217,-0.029734,0.001187,-0.981848,-0.006706,-0.007615,-0.003954,0,-0.000198,-0.00008,0.004601,0.022986,-0.003602,22.417988,54.488422,3.600104,0,0,-0.170759,0.08948,0.334504,-0.058543,-0.004799,-0.023065,0.089533,0.334481,0,125085,125137,125201,125239 -5.266218,-0.028758,0.000699,-0.983557,-0.006706,-0.007615,-0.005019,0,0.003009,0.001767,0.007345,0.02517,0.028316,27.452572,58.49799,340.210205,0,0,-0.171418,0.089692,0.334379,-0.058512,-0.004336,-0.023403,0.089533,0.334481,0,125331,126067,126129,125503 -5.271219,-0.028758,0.001676,-0.983557,-0.006706,-0.007615,-0.005019,0,-0.001602,-0.000906,0.003058,0.022462,-0.000866,19.585262,53.526955,42.380276,0,0,-0.171097,0.089578,0.334438,-0.058539,-0.00466,-0.023367,0.089533,0.334481,0,125642,125766,125834,125788 -5.27622,-0.02949,0.000455,-0.98258,-0.006706,-0.007615,-0.003954,0,-0.001602,-0.000906,0.003058,0.022462,-0.000866,19.585262,53.526955,31.519001,0,0,-0.171097,0.089578,0.334438,-0.058539,-0.00466,-0.023367,0.089533,0.334481,0,125653,125755,125823,125799 -5.281221,-0.029734,0.000211,-0.98258,-0.006706,-0.008679,-0.00289,0,-0.000414,-0.000176,0.004482,0.022667,-0.006815,24.151144,53.903599,-40.054131,0,0,-0.1709,0.089507,0.334474,-0.058565,-0.004896,-0.022843,0.089533,0.334481,0,125719,125688,125747,125876 -5.286222,-0.030223,0.000699,-0.98258,-0.006706,-0.007615,-0.00289,0,-0.000414,-0.000176,0.004482,0.022667,-0.006815,22.19816,53.903599,-40.054131,0,0,-0.1709,0.089507,0.334474,-0.058565,-0.004896,-0.022843,0.089533,0.334481,0,126660,126625,126688,126813 -5.291224,-0.030223,0.001187,-0.984045,-0.006706,-0.008679,-0.003954,0,-0.000414,-0.000176,0.004482,0.022667,-0.006815,24.151144,53.903599,-29.19286,0,0,-0.1709,0.089507,0.334474,-0.058565,-0.004896,-0.022843,0.089533,0.334481,0,126648,126638,126697,126804 -5.296225,-0.030467,0.002164,-0.985021,-0.006706,-0.007615,-0.005019,0,-0.000414,-0.000176,0.004482,0.022667,-0.006815,22.19816,53.903599,-18.331587,0,0,-0.1709,0.089507,0.334474,-0.058565,-0.004896,-0.022843,0.089533,0.334481,0,126639,126646,126710,126791 -5.301226,-0.030955,0.001676,-0.984777,-0.006706,-0.007615,-0.005019,0,-0.000414,-0.000176,0.004482,0.022667,-0.006815,22.19816,53.903599,-18.331587,0,0,-0.1709,0.089507,0.334474,-0.058565,-0.004896,-0.022843,0.089533,0.334481,0,126639,126646,126710,126791 -5.306227,-0.029734,0.000943,-0.984533,-0.006706,-0.007615,-0.005019,0,-0.000414,-0.000176,0.004482,0.022667,-0.006815,22.19816,53.903599,-18.331587,0,0,-0.1709,0.089507,0.334474,-0.058565,-0.004896,-0.022843,0.089533,0.334481,0,126639,126646,126710,126791 -5.311228,-0.02949,-0.000521,-0.984045,-0.006706,-0.007615,-0.00289,0,0.002763,0.001579,0.007409,0.024988,0.029534,27.570881,58.162598,330.914001,0,0,-0.171538,0.089696,0.334365,-0.058575,-0.004646,-0.023409,0.089533,0.334481,0,126765,127482,127543,126936 -5.316229,-0.029246,0.000943,-0.984045,-0.006706,-0.007615,-0.000762,0,-0.002188,-0.001213,0.002554,0.02124,-0.005583,18.66073,51.28458,-49.201973,0,0,-0.171061,0.089522,0.334459,-0.058573,-0.004742,-0.022453,0.089533,0.334481,0,127161,127100,127165,127301 -5.32123,-0.029246,-0.000521,-0.984289,-0.006706,-0.008679,-0.000762,0,0.000498,0.00039,0.005585,0.023048,0.000535,26.176615,54.602543,13.231578,0,0,-0.171031,0.089502,0.334462,-0.058585,-0.005087,-0.022658,0.089533,0.334481,0,127087,127166,127223,127249 -5.326231,-0.031443,0.000455,-0.984533,-0.006706,-0.007615,-0.000762,0,0.000498,0.00039,0.005585,0.023048,0.000535,24.223631,54.602543,13.231578,0,0,-0.171031,0.089502,0.334462,-0.058585,-0.005087,-0.022658,0.089533,0.334481,0,127089,127164,127225,127247 -5.331232,-0.031199,0.001187,-0.984777,-0.006706,-0.008679,-0.001826,0,0.000498,0.00039,0.005585,0.023048,0.000535,26.176615,54.602543,24.092852,0,0,-0.171031,0.089502,0.334462,-0.058585,-0.005087,-0.022658,0.089533,0.334481,0,127609,127709,127766,127770 -5.336233,-0.030955,0.000699,-0.985021,-0.005642,-0.00655,-0.001826,0,0.000498,0.00039,0.005585,0.023048,0.000535,22.270647,52.649559,24.092852,0,0,-0.171031,0.089502,0.334462,-0.058585,-0.005087,-0.022658,0.089533,0.334481,0,127614,127707,127768,127764 -5.341234,-0.02949,0.001432,-0.98551,-0.006706,-0.007615,-0.001826,0,0.000498,0.00039,0.005585,0.023048,0.000535,24.223631,54.602543,24.092852,0,0,-0.171031,0.089502,0.334462,-0.058585,-0.005087,-0.022658,0.089533,0.334481,0,127611,127707,127768,127768 -5.346235,-0.02827,0.000455,-0.984045,-0.006706,-0.007615,-0.001826,0,0.000498,0.00039,0.005585,0.023048,0.000535,24.223631,54.602543,24.092852,0,0,-0.171031,0.089502,0.334462,-0.058585,-0.005087,-0.022658,0.089533,0.334481,0,127611,127707,127768,127768 -5.351236,-0.027293,0.001432,-0.985021,-0.005642,-0.007615,-0.001826,0,0.000498,0.00039,0.005585,0.023048,0.000535,24.223631,52.649559,24.092852,0,0,-0.171031,0.089502,0.334462,-0.058585,-0.005087,-0.022658,0.089533,0.334481,0,127683,127779,127836,127836 -5.356237,-0.02949,-0.001254,-0.985754,-0.006706,-0.007615,-0.001826,0,-0.001421,-0.000994,0.003728,0.021849,-0.012794,20.814529,52.403233,-111.94268,0,0,-0.170729,0.089412,0.334524,-0.058605,-0.005148,-0.022843,0.089533,0.334481,0,127822,127640,127703,127969 -5.361238,-0.030467,-0.003451,-0.986242,-0.006706,-0.009743,-0.00289,0,0.000917,0.00069,0.006251,0.022998,0.006549,29.350765,54.51115,96.33149,0,0,-0.171104,0.089501,0.334451,-0.058614,-0.005333,-0.022307,0.089533,0.334481,0,127603,127855,127905,127771 -5.36624,-0.031932,-0.000277,-0.985021,-0.006706,-0.007615,-0.00289,0,0.000917,0.00069,0.006251,0.022998,0.006549,25.444798,54.51115,96.33149,0,0,-0.171104,0.089501,0.334451,-0.058614,-0.005333,-0.022307,0.089533,0.334481,0,127607,127851,127909,127767 -5.371241,-0.031443,0.002164,-0.984777,-0.006706,-0.007615,-0.003954,0,0.000738,0.000053,0.00554,0.022999,0.01198,24.140472,54.513199,162.61908,0,0,-0.171302,0.089578,0.334429,-0.05857,-0.004802,-0.022946,0.089533,0.334481,0,127542,127916,127976,127700 -5.376242,-0.030711,0.00192,-0.985754,-0.007771,-0.008679,-0.003954,0,0.000738,0.000053,0.00554,0.022999,0.01198,26.093456,56.466183,162.61908,0,0,-0.171302,0.089578,0.334429,-0.05857,-0.004802,-0.022946,0.089533,0.334481,0,127645,128023,128083,127810 -5.381243,-0.027537,0.003873,-0.98258,-0.005642,-0.007615,-0.001826,0,0.000738,0.000053,0.00554,0.022999,0.01198,24.140472,52.560215,140.896545,0,0,-0.171302,0.089578,0.334429,-0.05857,-0.004802,-0.022946,0.089533,0.334481,0,127673,128003,128060,127826 -5.386244,-0.028758,0.000943,-0.985754,-0.005642,-0.008679,-0.000762,0,0.000738,0.000053,0.00554,0.022999,0.01198,26.093456,52.560215,130.035263,0,0,-0.171302,0.089578,0.334429,-0.05857,-0.004802,-0.022946,0.089533,0.334481,0,127682,127994,128047,127839 -5.391245,-0.031443,-0.007846,-0.986975,-0.006706,-0.008679,-0.000762,0,0.000738,0.000053,0.00554,0.022999,0.01198,26.093456,54.513199,130.035263,0,0,-0.171302,0.089578,0.334429,-0.05857,-0.004802,-0.022946,0.089533,0.334481,0,127680,127992,128049,127841 -5.396246,-0.029246,-0.003451,-0.987707,-0.006706,-0.008679,-0.000762,0,0.000738,0.000053,0.00554,0.022999,0.01198,26.093456,54.513199,130.035263,0,0,-0.171302,0.089578,0.334429,-0.05857,-0.004802,-0.022946,0.089533,0.334481,0,127508,127820,127877,127669 -5.401247,-0.033885,0.002408,-0.986975,-0.005642,-0.005486,-0.003954,0,0.000738,0.000053,0.00554,0.022999,0.01198,20.234505,52.560215,162.61908,0,0,-0.171302,0.089578,0.334429,-0.05857,-0.004802,-0.022946,0.089533,0.334481,0,127483,127849,127913,127629 -5.406248,-0.030955,0.005826,-0.988439,-0.008835,-0.009743,-0.005019,0,0.000117,0.000229,0.004757,0.023526,0.013648,26.609304,59.385765,190.508759,0,0,-0.171604,0.08966,0.334376,-0.058601,-0.00464,-0.023297,0.089533,0.334481,0,127442,127876,127942,127614 -5.411249,-0.023875,0.009,-0.98551,-0.004578,-0.00655,-0.003954,0,-0.003814,-0.002291,0.001382,0.020038,-0.029715,14.556548,45.173653,-262.908295,0,0,-0.170753,0.089388,0.334535,-0.058619,-0.005196,-0.022329,0.089533,0.334481,0,127922,127425,127486,128041 -5.41625,-0.033641,0.002652,-0.986242,-0.005642,-0.007615,-0.000762,0,-0.003814,-0.002291,0.001382,0.020038,-0.029715,16.509533,47.126637,-295.492096,0,0,-0.170753,0.089388,0.334535,-0.058619,-0.005196,-0.022329,0.089533,0.334481,0,127950,127392,127454,128078 -5.421251,-0.030223,-0.007113,-0.985754,-0.005642,-0.008679,-0.001826,0,0.003304,0.002203,0.008102,0.024518,0.018864,30.794132,55.348377,211.161316,0,0,-0.171214,0.089528,0.334435,-0.058643,-0.004798,-0.022315,0.089533,0.334481,0,127421,127905,127954,127593 -5.426252,-0.026805,-0.004428,-0.985998,-0.005642,-0.007615,-0.003954,0,0.003304,0.002203,0.008102,0.024518,0.018864,28.841148,55.348377,232.88385,0,0,-0.171214,0.089528,0.334435,-0.058643,-0.004798,-0.022315,0.089533,0.334481,0,127401,127925,127978,127570 -5.431253,-0.037547,0.000455,-0.985021,-0.007771,-0.00655,-0.00289,0,0.003304,0.002203,0.008102,0.024518,0.018864,26.888165,59.254345,222.022583,0,0,-0.171214,0.089528,0.334435,-0.058643,-0.004798,-0.022315,0.089533,0.334481,0,127410,127908,127973,127583 -5.436255,-0.026072,0.008756,-0.985021,-0.006706,-0.007615,-0.00289,0,0.003304,0.002203,0.008102,0.024518,0.018864,28.841148,57.301361,222.022583,0,0,-0.171214,0.089528,0.334435,-0.058643,-0.004798,-0.022315,0.089533,0.334481,0,127410,127912,127969,127583 -5.441256,-0.028025,0.006314,-0.984533,-0.005642,-0.00655,-0.001826,0,0.003304,0.002203,0.008102,0.024518,0.018864,26.888165,55.348377,211.161316,0,0,-0.171214,0.089528,0.334435,-0.058643,-0.004798,-0.022315,0.089533,0.334481,0,127499,127975,128032,127664 -5.446257,-0.035105,-0.000521,-0.987463,-0.007771,-0.008679,-0.001826,0,0.003304,0.002203,0.008102,0.024518,0.018864,30.794132,59.254345,211.161316,0,0,-0.171214,0.089528,0.334435,-0.058643,-0.004798,-0.022315,0.089533,0.334481,0,127491,127975,128032,127671 -5.451258,-0.025828,-0.003695,-0.987951,-0.004578,-0.008679,-0.00289,0,0.003304,0.002203,0.008102,0.024518,0.018864,30.794132,53.395393,222.022583,0,0,-0.171214,0.089528,0.334435,-0.058643,-0.004798,-0.022315,0.089533,0.334481,0,127486,127992,128037,127655 -5.456259,-0.03535,-0.002719,-0.98258,-0.006706,-0.005486,-0.00289,0,0.00177,0.000061,0.001565,0.019566,0.029183,12.939851,48.213928,327.330322,0,0,-0.17174,0.089741,0.334374,-0.058444,0.000205,-0.019506,0.089533,0.334481,0,127404,128085,128155,127526 -5.46126,-0.02827,0.009,-0.983312,-0.008835,-0.008679,-0.00289,0,-0.002548,-0.000958,0.002688,0.022251,-0.015588,20.858793,57.046219,-129.596481,0,0,-0.170844,0.089464,0.334509,-0.058576,-0.005235,-0.023209,0.089533,0.334481,0,127950,127733,127805,128106 -5.466261,-0.027293,0.003141,-0.982824,-0.004578,-0.007615,-0.001826,0,0.001877,0.001258,0.006708,0.024293,0.008529,26.283838,52.981937,105.682549,0,0,-0.171056,0.089534,0.334443,-0.058608,-0.004831,-0.023035,0.089533,0.334481,0,127714,127977,128031,127872 -5.471262,-0.032176,0.000699,-0.987219,-0.007771,-0.007615,-0.000762,0,0.001877,0.001258,0.006708,0.024293,0.008529,26.283838,58.840885,94.821274,0,0,-0.171056,0.089534,0.334443,-0.058608,-0.004831,-0.023035,0.089533,0.334481,0,127719,127961,128026,127889 -5.476263,-0.02827,-0.002963,-0.986975,-0.004578,-0.008679,-0.00289,0,0.001877,0.001258,0.006708,0.024293,0.008529,28.236822,52.981937,116.543823,0,0,-0.171056,0.089534,0.334443,-0.058608,-0.004831,-0.023035,0.089533,0.334481,0,127701,127990,128040,127863 -5.481264,-0.031687,-0.000521,-0.983557,-0.006706,-0.00655,-0.001826,0,0.001877,0.001258,0.006708,0.024293,0.008529,24.330854,56.887905,105.682549,0,0,-0.171056,0.089534,0.334443,-0.058608,-0.004831,-0.023035,0.089533,0.334481,0,127712,127972,128037,127874 -5.486265,-0.031932,0.009,-0.983557,-0.007771,-0.007615,-0.001826,0,0.001877,0.001258,0.006708,0.024293,0.008529,26.283838,58.840885,105.682549,0,0,-0.171056,0.089534,0.334443,-0.058608,-0.004831,-0.023035,0.089533,0.334481,0,127630,127894,127959,127800 -5.491266,-0.027293,0.003629,-0.982824,-0.004578,-0.007615,-0.001826,0,0.001877,0.001258,0.006708,0.024293,0.008529,26.283838,52.981937,105.682549,0,0,-0.171056,0.089534,0.334443,-0.058608,-0.004831,-0.023035,0.089533,0.334481,0,127636,127899,127953,127794 -5.496267,-0.028514,-0.002475,-0.988684,-0.006706,-0.008679,-0.00289,0,0.000294,-0.000001,0.004688,0.023624,0.016603,24.529318,55.660538,198.938156,0,0,-0.171618,0.089743,0.334346,-0.058582,-0.004394,-0.023625,0.089533,0.334481,0,127541,127988,128051,127702 -5.501268,-0.030955,-0.001742,-0.98673,-0.004578,-0.008679,-0.003954,0,-0.003758,-0.002112,0.001268,0.020961,-0.028052,18.253714,46.868111,-245.933594,0,0,-0.170797,0.089479,0.334499,-0.058604,-0.005026,-0.023073,0.089533,0.334481,0,128001,127546,127603,128132 -5.506269,-0.030955,-0.000766,-0.988195,-0.006706,-0.007615,-0.006083,0,-0.003758,-0.002112,0.001268,0.020961,-0.028052,16.30073,50.774078,-224.211044,0,0,-0.170797,0.089479,0.334499,-0.058604,-0.005026,-0.023073,0.089533,0.334481,0,129151,128735,128804,129285 -5.511271,-0.030955,0.005826,-0.98551,-0.007771,-0.007615,-0.005019,0,0.001562,0.000447,0.006628,0.024129,-0.001877,26.137787,58.539589,32.065151,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,128877,128993,129058,129046 -5.516272,-0.027537,0.002164,-0.98551,-0.004578,-0.007615,-0.003954,0,0.001562,0.000447,0.006628,0.024129,-0.001877,26.137787,52.680641,21.203878,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,128893,128988,129041,129051 -5.521273,-0.02949,-0.004916,-0.988439,-0.006706,-0.008679,-0.001826,0,0.001562,0.000447,0.006628,0.024129,-0.001877,28.090771,56.586609,-0.518666,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,128909,128964,129021,129079 -5.526274,-0.030711,-0.004428,-0.981848,-0.004578,-0.007615,-0.005019,0,0.001562,0.000447,0.006628,0.024129,-0.001877,26.137787,52.680641,32.065151,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,128883,128999,129052,129040 -5.531275,-0.03242,0.003141,-0.988684,-0.009899,-0.008679,-0.005019,0,0.001562,0.000447,0.006628,0.024129,-0.001877,28.090771,62.44556,32.065151,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,130111,130231,130300,130292 -5.536276,-0.027293,0.005338,-0.981848,-0.005642,-0.005486,-0.005019,0,0.001562,0.000447,0.006628,0.024129,-0.001877,22.231819,54.633625,32.065151,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,130125,130233,130298,130278 -5.541277,-0.026561,-0.000277,-0.988195,-0.004578,-0.010807,-0.00289,0,0.001562,0.000447,0.006628,0.024129,-0.001877,31.996738,52.680641,10.342608,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,130138,130223,130265,130308 -5.546278,-0.032176,-0.003695,-0.98258,-0.005642,-0.00655,-0.003954,0,0.001562,0.000447,0.006628,0.024129,-0.001877,24.184803,54.633625,21.203878,0,0,-0.170804,0.089495,0.334521,-0.058566,-0.005066,-0.023682,0.089533,0.334481,0,130133,130224,130285,130291 -5.551279,-0.028758,-0.001986,-0.985021,-0.005642,-0.009743,-0.005019,0,-0.000035,0.000651,0.00482,0.023596,0.004033,26.725338,53.655899,92.373955,0,0,-0.170934,0.089533,0.334462,-0.058607,-0.004855,-0.022945,0.089533,0.334481,0,131816,132054,132108,131977 -5.55628,-0.032908,0.006803,-0.98551,-0.008835,-0.00655,-0.001826,0,0.000428,-0.000022,0.004792,0.022808,0.007229,20.814304,58.06905,92.410576,0,0,-0.171212,0.089623,0.334417,-0.058594,-0.004364,-0.02283,0.089533,0.334481,0,131817,132044,132118,131975 -5.561281,-0.026072,-0.000033,-0.987951,-0.003514,-0.009743,-0.001826,0,0.000622,0.000232,0.004697,0.023586,0.012036,26.49963,49.732288,141.47171,0,0,-0.171375,0.089679,0.3344,-0.058606,-0.004075,-0.023354,0.089533,0.334481,0,131771,132107,132153,131923 -5.566282,-0.031199,-0.005893,-0.990393,-0.006706,-0.007615,-0.000762,0,0.000622,0.000232,0.004697,0.023586,0.012036,22.59366,55.59124,130.610428,0,0,-0.171375,0.089679,0.3344,-0.058606,-0.004075,-0.023354,0.089533,0.334481,0,131780,132086,132152,131936 -5.571283,-0.031199,-0.002719,-0.986242,-0.005642,-0.00655,-0.00289,0,0.000622,0.000232,0.004697,0.023586,0.012036,20.640678,53.638256,152.332977,0,0,-0.171375,0.089679,0.3344,-0.058606,-0.004075,-0.023354,0.089533,0.334481,0,133513,133859,133925,133661 -5.576284,-0.029734,0.002408,-0.987707,-0.010963,-0.009743,-0.003954,0,0.000622,0.000232,0.004697,0.023586,0.012036,26.49963,63.403172,163.194244,0,0,-0.171375,0.089679,0.3344,-0.058606,-0.004075,-0.023354,0.089533,0.334481,0,133486,133866,133940,133666 -5.581285,-0.02827,0.001432,-0.983801,-0.003514,-0.004422,-0.005019,0,0.000622,0.000232,0.004697,0.023586,0.012036,16.734711,49.732288,174.055527,0,0,-0.171375,0.089679,0.3344,-0.058606,-0.004075,-0.023354,0.089533,0.334481,0,133499,133881,133947,133632 -5.586287,-0.027781,-0.006381,-0.987707,-0.007771,-0.011872,-0.005019,0,0.000622,0.000232,0.004697,0.023586,0.012036,30.405598,57.544224,174.055527,0,0,-0.171375,0.089679,0.3344,-0.058606,-0.004075,-0.023354,0.089533,0.334481,0,133477,133886,133941,133653 -5.591288,-0.030467,-0.006137,-0.986486,-0.003514,-0.002294,-0.006083,0,0.000622,0.000232,0.004697,0.023586,0.012036,12.828743,49.732288,184.916794,0,0,-0.171375,0.089679,0.3344,-0.058606,-0.004075,-0.023354,0.089533,0.334481,0,133492,133888,133961,133617 -5.596289,-0.030223,0.00192,-0.987219,-0.010963,-0.010807,-0.003954,0,-0.000188,-0.000032,0.003428,0.023097,0.009674,26.123989,62.505417,139.088516,0,0,-0.171482,0.089686,0.33439,-0.058599,-0.003617,-0.02313,0.089533,0.334481,0,135103,135433,135506,135280 -5.60129,-0.027537,0.001187,-0.985754,-0.003514,-0.005486,-0.00289,0,-0.000021,0.000074,0.004324,0.023455,0.011298,18.002274,49.490749,144.804291,0,0,-0.17154,0.08968,0.334385,-0.058636,-0.004345,-0.023381,0.089533,0.334481,0,135118,135444,135507,135253 -5.606291,-0.026805,-0.005404,-0.987219,-0.007771,-0.011872,-0.00289,0,-0.000021,0.000074,0.004324,0.023455,0.011298,29.720177,57.302685,144.804291,0,0,-0.17154,0.08968,0.334385,-0.058636,-0.004345,-0.023381,0.089533,0.334481,0,135099,135448,135503,135273 -5.611292,-0.031199,-0.004916,-0.988439,-0.003514,-0.004422,-0.00289,0,-0.000021,0.000074,0.004324,0.023455,0.011298,16.04929,49.490749,144.804291,0,0,-0.17154,0.08968,0.334385,-0.058636,-0.004345,-0.023381,0.089533,0.334481,0,135120,135442,135509,135251 -5.616293,-0.030223,0.00607,-0.98966,-0.010963,-0.009743,-0.003954,0,-0.000021,0.000074,0.004324,0.023455,0.011298,25.814209,63.161636,155.665558,0,0,-0.17154,0.08968,0.334385,-0.058636,-0.004345,-0.023381,0.089533,0.334481,0,136439,136802,136877,136617 -5.621294,-0.028514,0.00192,-0.989172,-0.00245,-0.005486,-0.003954,0,-0.000021,0.000074,0.004324,0.023455,0.011298,18.002274,47.537766,155.665558,0,0,-0.17154,0.08968,0.334385,-0.058636,-0.004345,-0.023381,0.089533,0.334481,0,136462,136810,136869,136593 -5.626295,-0.028025,-0.004672,-0.988439,-0.008835,-0.011872,-0.00289,0,-0.000021,0.000074,0.004324,0.023455,0.011298,29.720177,59.255669,144.804291,0,0,-0.17154,0.08968,0.334385,-0.058636,-0.004345,-0.023381,0.089533,0.334481,0,136450,136799,136858,136628 -5.631296,-0.030223,-0.000277,-0.990148,-0.003514,-0.003358,-0.005019,0,0.000245,0.000267,0.004573,0.023429,0.014976,14.554445,49.443851,204.057785,0,0,-0.171656,0.089697,0.334364,-0.058644,-0.004328,-0.023162,0.089533,0.334481,0,136415,136853,136922,136543 -5.636297,-0.031932,0.007047,-0.987951,-0.012028,-0.009743,-0.006083,0,-0.000452,-0.000184,0.003608,0.022688,0.007837,24.500225,63.706596,142.058044,0,0,-0.171546,0.089644,0.334377,-0.058668,-0.004059,-0.022872,0.089533,0.334481,0,136453,136786,136865,136630 -5.641298,-0.028514,0.000455,-0.987463,-0.003514,-0.00655,-0.003954,0,0.001193,0.00093,0.005827,0.023551,0.021722,22.713921,49.667488,262.052856,0,0,-0.171803,0.089719,0.334314,-0.058688,-0.004634,-0.022621,0.089533,0.334481,0,137637,138207,138261,137782 -5.646299,-0.029979,-0.006137,-0.98551,-0.008835,-0.010807,-0.001826,0,0.001193,0.00093,0.005827,0.023551,0.021722,30.525854,59.432407,240.330307,0,0,-0.171803,0.089719,0.334314,-0.058688,-0.004634,-0.022621,0.089533,0.334481,0,137641,138183,138241,137821 -5.6513,-0.02949,0.000943,-0.985998,-0.004578,-0.003358,-0.003954,0,-0.002384,-0.001507,0.002753,0.020503,-0.007769,11.214758,46.027367,-38.933117,0,0,-0.17135,0.089577,0.334399,-0.058714,-0.005138,-0.02201,0.089533,0.334481,0,137953,137898,137967,138068 -5.656301,-0.030711,0.005094,-0.988684,-0.010963,-0.008679,-0.005019,0,-0.002384,-0.001507,0.002753,0.020503,-0.007769,20.979677,57.74527,-28.071846,0,0,-0.17135,0.089577,0.334399,-0.058714,-0.005138,-0.02201,0.089533,0.334481,0,137921,137907,137980,138078 -5.661303,-0.02534,-0.003207,-0.986242,-0.00245,-0.007615,-0.00289,0,-0.002384,-0.001507,0.002753,0.020503,-0.007769,19.026693,42.121399,-49.794388,0,0,-0.17135,0.089577,0.334399,-0.058714,-0.005138,-0.02201,0.089533,0.334481,0,139379,139318,139364,139501 -5.666304,-0.031443,-0.007113,-0.988439,-0.007771,-0.00655,-0.003954,0,-0.002384,-0.001507,0.002753,0.020503,-0.007769,17.073709,51.886318,-38.933117,0,0,-0.17135,0.089577,0.334399,-0.058714,-0.005138,-0.02201,0.089533,0.334481,0,139360,139317,139386,139498 -5.671305,-0.027781,0.005094,-0.989172,-0.005642,-0.002294,-0.003954,0,-0.002384,-0.001507,0.002753,0.020503,-0.007769,9.261774,47.98035,-38.933117,0,0,-0.17135,0.089577,0.334399,-0.058714,-0.005138,-0.02201,0.089533,0.334481,0,139372,139313,139390,139487 -5.676306,-0.05366,-0.002475,-0.987707,-0.005642,-0.007615,-0.001826,0,-0.002384,-0.001507,0.002753,0.020503,-0.007769,19.026693,47.98035,-60.655663,0,0,-0.17135,0.089577,0.334399,-0.058714,-0.005138,-0.02201,0.089533,0.334481,0,139384,139301,139359,139518 -5.681307,-0.051707,-0.003695,-0.984045,-0.005642,-0.007615,-0.00289,0,-0.002384,-0.001507,0.002753,0.020503,-0.007769,19.026693,47.98035,-49.794388,0,0,-0.17135,0.089577,0.334399,-0.058714,-0.005138,-0.02201,0.089533,0.334481,0,140467,140406,140464,140601 -5.686308,-0.046824,-0.000277,-0.989416,-0.005642,-0.003358,-0.006083,0,0.000876,0.000416,0.00577,0.02194,0.006028,16.74987,50.617619,123.601463,0,0,-0.171333,0.089582,0.334426,-0.058749,-0.004893,-0.021524,0.089533,0.334481,0,140294,140574,140642,140428 -5.691309,-0.044871,-0.001498,-0.989172,-0.007771,-0.008679,-0.006083,0,-0.00189,-0.001351,0.002557,0.021103,-0.007703,20.618574,52.987671,-16.530363,0,0,-0.171038,0.089469,0.334513,-0.058723,-0.004446,-0.022455,0.089533,0.334481,0,140427,140436,140500,140575 -5.69631,-0.040232,-0.013949,-0.983312,-0.00245,-0.004422,-0.005019,0,-0.00189,-0.001351,0.002557,0.021103,-0.007703,12.806639,43.222752,-27.39164,0,0,-0.171038,0.089469,0.334513,-0.058723,-0.004446,-0.022455,0.089533,0.334481,0,140456,140427,140488,140568 -5.701311,-0.040477,-0.0181,-0.992102,-0.007771,-0.00655,-0.008211,0,-0.00189,-0.001351,0.002557,0.021103,-0.007703,16.712606,52.987671,5.192179,0,0,-0.171038,0.089469,0.334513,-0.058723,-0.004446,-0.022455,0.089533,0.334481,0,140410,140453,140526,140549 -5.706312,-0.037303,-0.009311,-0.993078,-0.007771,-0.005486,-0.008211,0,-0.00189,-0.001351,0.002557,0.021103,-0.007703,14.759623,52.987671,5.192179,0,0,-0.171038,0.089469,0.334513,-0.058723,-0.004446,-0.022455,0.089533,0.334481,0,140739,140778,140855,140874 -5.711313,-0.037303,-0.013705,-0.98673,-0.005642,-0.010807,-0.007147,0,-0.00189,-0.001351,0.002557,0.021103,-0.007703,24.524542,49.081703,-5.669089,0,0,-0.171038,0.089469,0.334513,-0.058723,-0.004446,-0.022455,0.089533,0.334481,0,140744,140781,140830,140891 -5.716314,-0.037547,-0.014193,-0.988439,-0.004578,-0.004422,-0.006083,0,-0.00189,-0.001351,0.002557,0.021103,-0.007703,12.806639,47.128719,-16.530363,0,0,-0.171038,0.089469,0.334513,-0.058723,-0.004446,-0.022455,0.089533,0.334481,0,140768,140761,140829,140888 -5.721315,-0.033885,-0.004672,-0.996496,-0.007771,-0.004422,-0.007147,0,-0.00189,-0.001351,0.002557,0.021103,-0.007703,12.806639,52.987671,-5.669089,0,0,-0.171038,0.089469,0.334513,-0.058723,-0.004446,-0.022455,0.089533,0.334481,0,140751,140766,140846,140883 -5.726316,-0.034129,-0.005648,-0.989416,-0.003514,-0.010807,-0.008211,0,0.002247,0.001689,0.006713,0.023274,0.024394,32.151123,49.158531,332.76297,0,0,-0.171763,0.089696,0.334338,-0.058799,-0.004466,-0.021585,0.089533,0.334481,0,140619,141349,141383,140782 -5.731318,-0.038279,-0.012729,-0.983068,-0.003514,-0.004422,-0.009276,0,-0.00063,-0.00104,0.000136,0.017462,0.008956,8.365305,38.492371,186.071259,0,0,-0.171635,0.089721,0.334401,-0.058685,-0.000766,-0.018502,0.089533,0.334481,0,140801,141189,141250,140894 -5.736319,-0.031199,-0.003939,-0.996496,-0.006706,-0.003358,-0.01034,0,-0.00063,-0.00104,0.000136,0.017462,0.008956,6.412322,44.351322,196.932526,0,0,-0.171635,0.089721,0.334401,-0.058685,-0.000766,-0.018502,0.089533,0.334481,0,140786,141192,141268,140887 -5.74132,-0.031932,-0.004672,-0.994543,-0.00245,-0.00655,-0.01034,0,-0.00063,-0.00104,0.000136,0.017462,0.008956,12.271273,36.539387,196.932526,0,0,-0.171635,0.089721,0.334401,-0.058685,-0.000766,-0.018502,0.089533,0.334481,0,140788,141206,141255,140885 -5.746321,-0.038768,-0.009066,-0.983068,-0.003514,-0.003358,-0.009276,0,-0.00063,-0.00104,0.000136,0.017462,0.008956,6.412322,38.492371,186.071259,0,0,-0.171635,0.089721,0.334401,-0.058685,-0.000766,-0.018502,0.089533,0.334481,0,140803,141187,141252,140892 -5.751322,-0.029002,-0.001498,-0.993811,-0.005642,-0.003358,-0.009276,0,-0.00063,-0.00104,0.000136,0.017462,0.008956,6.412322,42.398338,186.071259,0,0,-0.171635,0.089721,0.334401,-0.058685,-0.000766,-0.018502,0.089533,0.334481,0,140629,141014,141086,140726 -5.756323,-0.028758,-0.002719,-0.992834,-0.001385,-0.007615,-0.01034,0,-0.00063,-0.00104,0.000136,0.017462,0.008956,14.224257,34.586403,196.932526,0,0,-0.171635,0.089721,0.334401,-0.058685,-0.000766,-0.018502,0.089533,0.334481,0,140618,141040,141081,140715 -5.761324,-0.033152,-0.004428,-0.979895,-0.003514,-0.003358,-0.011404,0,0.000793,0.00087,0.00476,0.023036,0.018705,14.896615,48.721611,307.281525,0,0,-0.17188,0.089803,0.334329,-0.058791,-0.003967,-0.022166,0.089533,0.334481,0,140493,141137,141205,140620 -5.766325,-0.026316,0.001187,-0.993322,-0.003514,-0.004422,-0.011404,0,-0.002584,-0.001985,0.001884,0.019758,-0.011724,11.572102,42.70665,-3.261902,0,0,-0.171318,0.089636,0.33445,-0.05883,-0.004468,-0.021743,0.089533,0.334481,0,140812,140829,140891,140921 -5.771326,-0.028025,-0.003695,-0.991857,0.000743,-0.008679,-0.012468,0,-0.002584,-0.001985,0.001884,0.019758,-0.011724,19.384035,34.894714,7.599376,0,0,-0.171318,0.089636,0.33445,-0.05883,-0.004468,-0.021743,0.089533,0.334481,0,140790,140844,140875,140898 -5.776327,-0.033396,-0.003939,-0.97965,-0.001385,-0.002294,-0.01034,0,-0.002584,-0.001985,0.001884,0.019758,-0.011724,7.666134,38.800682,-14.123179,0,0,-0.171318,0.089636,0.33445,-0.05883,-0.004468,-0.021743,0.089533,0.334481,0,140819,140806,140869,140912 -5.781328,-0.027781,0.002164,-0.994787,-0.00245,-0.005486,-0.009276,0,-0.002584,-0.001985,0.001884,0.019758,-0.011724,13.525084,40.753666,-24.984447,0,0,-0.171318,0.089636,0.33445,-0.05883,-0.004468,-0.021743,0.089533,0.334481,0,140822,140799,140854,140931 -5.786329,-0.027537,-0.004184,-0.994787,-0.00245,-0.007615,-0.009276,0,-0.002584,-0.001985,0.001884,0.019758,-0.011724,17.431053,40.753666,-24.984447,0,0,-0.171318,0.089636,0.33445,-0.05883,-0.004468,-0.021743,0.089533,0.334481,0,140818,140803,140850,140935 -5.79133,-0.033396,-0.006869,-0.981359,-0.004578,-0.002294,-0.009276,0,-0.002584,-0.001985,0.001884,0.019758,-0.011724,7.666134,44.659634,-24.984447,0,0,-0.171318,0.089636,0.33445,-0.05883,-0.004468,-0.021743,0.089533,0.334481,0,141483,141449,141523,141588 -5.796331,-0.028514,-0.00101,-0.994543,-0.005642,-0.007615,-0.01034,0,0.002851,0.001411,0.006728,0.024491,0.023273,26.32082,55.298775,343.048279,0,0,-0.171684,0.089776,0.3344,-0.058794,-0.003877,-0.02308,0.089533,0.334481,0,141086,141825,141883,141249 -5.801332,-0.027537,-0.001986,-0.991125,-0.00245,-0.00655,-0.009276,0,-0.000558,-0.000362,0.003777,0.022416,0.015871,18.9522,45.631222,256.64212,0,0,-0.171841,0.089875,0.334369,-0.058866,-0.004335,-0.022778,0.089533,0.334481,0,141189,141740,141794,141318 -5.806334,-0.030467,-0.006381,-0.979162,-0.007771,-0.000165,-0.01034,0,-0.000558,-0.000362,0.003777,0.022416,0.015871,7.234297,55.396141,267.503418,0,0,-0.171841,0.089875,0.334369,-0.058866,-0.004335,-0.022778,0.089533,0.334481,0,141180,141730,141826,141306 -5.811335,-0.027781,-0.003451,-0.991857,-0.008835,-0.010807,-0.009276,0,-0.000558,-0.000362,0.003777,0.022416,0.015871,26.764133,57.349125,256.64212,0,0,-0.171841,0.089875,0.334369,-0.058866,-0.004335,-0.022778,0.089533,0.334481,0,141170,141737,141798,141338 -5.816336,-0.032908,0.000943,-0.983068,-0.004578,-0.00655,-0.01034,0,-0.000558,-0.000362,0.003777,0.022416,0.015871,18.9522,49.537189,267.503418,0,0,-0.171841,0.089875,0.334369,-0.058866,-0.004335,-0.022778,0.089533,0.334481,0,141899,142471,142533,142035 -5.821337,-0.031443,-0.001254,-0.980139,-0.007771,0.001963,-0.011404,0,-0.000558,-0.000362,0.003777,0.022416,0.015871,3.328329,55.396141,278.364685,0,0,-0.171841,0.089875,0.334369,-0.058866,-0.004335,-0.022778,0.089533,0.334481,0,141897,142461,142565,142015 -5.826338,-0.027049,-0.006381,-0.992346,-0.008835,-0.012936,-0.011404,0,-0.000558,-0.000362,0.003777,0.022416,0.015871,30.670101,57.349125,278.364685,0,0,-0.171841,0.089875,0.334369,-0.058866,-0.004335,-0.022778,0.089533,0.334481,0,141868,142486,142540,142044 -5.831339,-0.035838,0.003141,-0.983801,-0.004578,-0.000165,-0.011404,0,-0.000558,-0.000362,0.003777,0.022416,0.015871,7.234297,49.537189,278.364685,0,0,-0.171841,0.089875,0.334369,-0.058866,-0.004335,-0.022778,0.089533,0.334481,0,141899,142471,142555,142013 -5.83634,-0.030711,0.002408,-0.987219,-0.006706,0.00622,-0.012468,0,0.00036,0.000248,0.004678,0.02293,0.017142,-2.830561,54.386505,302.194122,0,0,-0.171952,0.08991,0.334343,-0.058906,-0.004318,-0.022682,0.089533,0.334481,0,142689,143287,143402,142792 -5.841341,-0.030711,-0.007113,-1.001379,-0.005642,-0.005486,-0.012468,0,0.001541,0.000542,0.005537,0.02303,0.03311,20.228611,52.616982,465.159515,0,0,-0.172315,0.09003,0.334298,-0.058898,-0.003996,-0.022488,0.089533,0.334481,0,142504,143475,143540,142650 -5.846342,-0.034617,-0.002475,-0.985021,-0.003514,0.004092,-0.01034,0,0.001541,0.000542,0.005537,0.02303,0.03311,2.651756,48.711014,443.436951,0,0,-0.172315,0.09003,0.334298,-0.058898,-0.003996,-0.022488,0.089533,0.334481,0,142548,143440,143532,142650 -5.851343,-0.026072,0.002164,-0.994787,-0.007771,0.005156,-0.009276,0,0.001541,0.000542,0.005537,0.02303,0.03311,0.698772,56.522949,432.575684,0,0,-0.172315,0.09003,0.334298,-0.058898,-0.003996,-0.022488,0.089533,0.334481,0,142553,143419,143531,142667 -5.856344,-0.028025,-0.007846,-0.998205,-0.007771,-0.002294,-0.008211,0,0.001541,0.000542,0.005537,0.02303,0.03311,14.369659,56.522949,421.714417,0,0,-0.172315,0.09003,0.334298,-0.058898,-0.003996,-0.022488,0.089533,0.334481,0,142550,143422,143506,142692 -5.861345,-0.034617,-0.006381,-0.981115,-0.010963,0.010477,-0.006083,0,0.001541,0.000542,0.005537,0.02303,0.03311,-9.066147,62.381901,399.991882,0,0,-0.172315,0.09003,0.334298,-0.058898,-0.003996,-0.022488,0.089533,0.334481,0,142877,143659,143802,142984 -5.866346,-0.029002,-0.006625,-0.996496,-0.012028,0.003028,-0.00289,0,0.001541,0.000542,0.005537,0.02303,0.03311,4.60474,64.334885,367.408051,0,0,-0.172315,0.09003,0.334298,-0.058898,-0.003996,-0.022488,0.089533,0.334481,0,142894,143638,143758,143032 -5.871347,-0.020701,-0.004428,-0.994543,-0.010963,0.000899,-0.001826,0,0.001541,0.000542,0.005537,0.02303,0.03311,8.510708,62.381901,356.546783,0,0,-0.172315,0.09003,0.334298,-0.058898,-0.003996,-0.022488,0.089533,0.334481,0,142903,143633,143741,143045 -5.876348,-0.02949,-0.004428,-0.979895,-0.016285,0.010477,-0.000762,0,-0.000958,-0.000044,0.003161,0.022352,0.020472,-13.426453,70.902969,216.710968,0,0,-0.17229,0.090001,0.334287,-0.058928,-0.004119,-0.022396,0.089533,0.334481,0,143056,143463,143632,143171 -5.88135,-0.033152,-0.003939,-0.990393,-0.010963,-0.007615,0.002431,0,-0.000101,-0.000009,0.003148,0.022277,0.019382,19.75123,60.999542,172.994553,0,0,-0.172217,0.089904,0.334293,-0.059043,-0.003249,-0.022286,0.089533,0.334481,0,143081,143466,143549,143242 -5.886351,-0.025096,-0.000521,-0.977697,-0.004578,0.000899,0.001367,0,-0.000101,-0.000009,0.003148,0.022277,0.019382,4.12736,49.281639,183.85582,0,0,-0.172217,0.089904,0.334293,-0.059043,-0.003249,-0.022286,0.089533,0.334481,0,143097,143473,143564,143204 -5.891352,-0.018748,0.003873,-0.974768,-0.006706,0.00622,-0.000762,0,-0.000101,-0.000009,0.003148,0.022277,0.019382,-5.637559,53.187607,205.578369,0,0,-0.172217,0.089904,0.334293,-0.059043,-0.003249,-0.022286,0.089533,0.334481,0,143081,143481,143599,143176 -5.896353,-0.027049,0.003385,-0.988684,-0.001385,-0.017193,0.001367,0,-0.000101,-0.000009,0.003148,0.022277,0.019382,37.328083,43.422691,183.85582,0,0,-0.172217,0.089904,0.334293,-0.059043,-0.003249,-0.022286,0.089533,0.334481,0,143070,143512,143524,143231 -5.901354,-0.038523,0.005338,-0.971105,0.005,0.001963,0.002431,0,-0.000101,-0.000009,0.003148,0.022277,0.019382,2.174376,31.704786,172.994553,0,0,-0.172217,0.089904,0.334293,-0.059043,-0.003249,-0.022286,0.089533,0.334481,0,143137,143487,143546,143204 -5.906355,-0.020213,0.007779,-0.985998,0.009257,-0.001229,-0.000762,0,-0.000101,-0.000009,0.003148,0.022277,0.019382,8.033327,23.892853,205.578369,0,0,-0.172217,0.089904,0.334293,-0.059043,-0.003249,-0.022286,0.089533,0.334481,0,143106,143533,143565,143170 -5.911356,-0.017039,0.007047,-0.99674,0.010321,-0.011872,-0.003954,0,0.000974,0.001111,0.004254,0.02396,0.035219,29.592064,25.028402,399.791321,0,0,-0.172536,0.089972,0.334213,-0.059051,-0.00328,-0.022848,0.089533,0.334481,0,142889,143748,143739,142998 -5.916357,-0.03242,0.004605,-0.984045,0.005,0.003028,-0.001826,0,0.000092,-0.000592,0.003343,0.021129,0.028122,0.578794,29.598093,305.645569,0,0,-0.17263,0.090035,0.334241,-0.059133,-0.003251,-0.02172,0.089533,0.334481,0,143008,143620,143678,143068 -5.921358,-0.034861,0.004361,-0.994055,0.009257,-0.010807,-0.00289,0,0.000576,0.000306,0.00422,0.021472,0.037082,27.577255,22.416849,407.945679,0,0,-0.172851,0.090079,0.334234,-0.059116,-0.003644,-0.021166,0.089533,0.334481,0,142886,143757,143746,142986 -5.926359,-0.032176,0.003141,-0.98673,0.009257,-0.000165,-0.003954,0,0.000576,0.000306,0.00422,0.021472,0.037082,8.047419,22.416849,418.806946,0,0,-0.172851,0.090079,0.334234,-0.059116,-0.003644,-0.021166,0.089533,0.334481,0,143471,144325,144354,143532 -5.93136,-0.028025,0.000943,-0.988684,-0.000321,0.012606,-0.006083,0,0.000576,0.000306,0.00422,0.021472,0.037082,-15.388388,39.993702,440.52951,0,0,-0.172851,0.090079,0.334234,-0.059116,-0.003644,-0.021166,0.089533,0.334481,0,143455,144306,144416,143505 -5.936361,-0.029734,-0.00809,-1.001379,-0.004578,-0.005486,-0.003954,0,0.000576,0.000306,0.00422,0.021472,0.037082,17.812336,47.805637,418.806946,0,0,-0.172851,0.090079,0.334234,-0.059116,-0.003644,-0.021166,0.089533,0.334481,0,143436,144309,144369,143567 -5.941362,-0.035838,-0.007357,-0.987219,-0.014156,0.01367,-0.00289,0,0.000576,0.000306,0.00422,0.021472,0.037082,-17.34137,65.382492,407.945679,0,0,-0.172851,0.090079,0.334234,-0.059116,-0.003644,-0.021166,0.089533,0.334481,0,143465,144246,144411,143561 -5.946363,-0.02827,-0.011264,-0.998693,-0.013092,0.010477,-0.005019,0,0.000576,0.000306,0.00422,0.021472,0.037082,-11.48242,63.429508,429.668213,0,0,-0.172851,0.090079,0.334234,-0.059116,-0.003644,-0.021166,0.089533,0.334481,0,144107,144943,145093,144211 -5.951365,-0.024363,-0.005648,-1.000402,-0.012028,0.00622,-0.006083,0,0.000576,0.000306,0.00422,0.021472,0.037082,-3.670485,61.476524,440.52951,0,0,-0.172851,0.090079,0.334234,-0.059116,-0.003644,-0.021166,0.089533,0.334481,0,144090,144964,145094,144206 -5.956366,-0.031443,-0.008334,-0.990637,-0.014156,0.027505,-0.007147,0,-0.001245,-0.00113,0.001655,0.019465,0.01087,-47.437782,61.697952,183.878616,0,0,-0.172118,0.089854,0.334456,-0.059229,-0.0029,-0.020595,0.089533,0.334481,0,144390,144663,144882,144419 -5.961367,-0.026805,-0.00809,-1.004553,-0.003514,0.008349,-0.007147,0,0.001672,0.001408,0.003845,0.022955,0.036733,-8.2655,48.5741,447.83609,0,0,-0.172502,0.089942,0.334383,-0.059249,-0.002172,-0.021547,0.089533,0.334481,0,144100,144979,145093,144181 -5.966368,-0.026316,-0.007113,-0.988195,-0.003514,0.018991,-0.008211,0,0.001672,0.001408,0.003845,0.022955,0.036733,-27.79534,48.5741,458.697357,0,0,-0.172502,0.089942,0.334383,-0.059249,-0.002172,-0.021547,0.089533,0.334481,0,144109,144971,145124,144151 -5.971369,-0.023631,-0.00809,-0.991613,-0.000321,0.023248,-0.012468,0,0.001672,0.001408,0.003845,0.022955,0.036733,-35.607273,42.715149,502.142456,0,0,-0.172502,0.089942,0.334383,-0.059249,-0.002172,-0.021547,0.089533,0.334481,0,144575,145508,145665,144589 -5.97637,-0.02241,-0.001742,-0.998205,-0.000321,0.004092,-0.012468,0,0.001672,0.001408,0.003845,0.022955,0.036733,-0.453567,42.715149,502.142456,0,0,-0.172502,0.089942,0.334383,-0.059249,-0.002172,-0.021547,0.089533,0.334481,0,144540,145543,145630,144625 -5.981371,-0.029002,-0.00101,-0.986486,-0.006706,0.021119,-0.013532,0,0.001672,0.001408,0.003845,0.022955,0.036733,-31.701307,54.433052,513.003723,0,0,-0.172502,0.089942,0.334383,-0.059249,-0.002172,-0.021547,0.089533,0.334481,0,144549,145511,145684,144594 -5.986372,-0.022654,-0.002719,-0.992346,-0.003514,0.005156,-0.013532,0,0.001672,0.001408,0.003845,0.022955,0.036733,-2.40655,48.5741,513.003723,0,0,-0.172502,0.089942,0.334383,-0.059249,-0.002172,-0.021547,0.089533,0.334481,0,144525,145547,145648,144618 -5.991373,-0.024607,-0.001742,-0.978674,-0.006706,0.005156,-0.011404,0,-0.000424,0.000106,0.001073,0.020859,0.029203,-7.493046,50.585514,414.431366,0,0,-0.172599,0.089955,0.334339,-0.059317,-0.001497,-0.020753,0.089533,0.334481,0,145106,145920,146036,145192 -5.996374,-0.023875,0.000699,-0.985021,-0.006706,0.018991,-0.01034,0,-0.000309,-0.000542,0.001918,0.020229,0.015359,-31.33102,49.430378,262.272339,0,0,-0.172256,0.089888,0.334412,-0.059399,-0.002227,-0.020771,0.089533,0.334481,0,145283,145745,145907,145319 -6.001375,-0.019725,-0.000766,-0.997717,-0.009899,-0.004422,-0.009276,0,-0.000309,-0.000542,0.001918,0.020229,0.015359,11.634622,55.289333,251.411087,0,0,-0.172256,0.089888,0.334412,-0.059399,-0.002227,-0.020771,0.089533,0.334481,0,145245,145771,145859,145379 -6.006376,-0.023387,0.000455,-0.985754,-0.020541,0.01367,-0.013532,0,-0.000309,-0.000542,0.001918,0.020229,0.015359,-21.566101,74.819168,294.856171,0,0,-0.172256,0.089888,0.334412,-0.059399,-0.002227,-0.020771,0.089533,0.334481,0,145215,145762,145955,145322 -6.011377,-0.025096,-0.005893,-0.992834,-0.021606,0.005156,-0.012468,0,-0.000309,-0.000542,0.001918,0.020229,0.015359,-5.942232,76.772156,283.994904,0,0,-0.172256,0.089888,0.334412,-0.059399,-0.002227,-0.020771,0.089533,0.334481,0,145174,145730,145895,145315 -6.016378,-0.029734,-0.001986,-0.988684,-0.021606,0.004092,-0.011404,0,-0.000309,-0.000542,0.001918,0.020229,0.015359,-3.989248,76.772156,273.133636,0,0,-0.172256,0.089888,0.334412,-0.059399,-0.002227,-0.020771,0.089533,0.334481,0,145183,145721,145882,145328 -6.021379,-0.029246,0.004605,-0.991125,-0.02267,0.025376,-0.014597,0,-0.000309,-0.000542,0.001918,0.020229,0.015359,-43.048923,78.725136,305.717438,0,0,-0.172256,0.089888,0.334412,-0.059399,-0.002227,-0.020771,0.089533,0.334481,0,145187,145712,145956,145258 -6.026381,-0.023387,-0.001742,-1.005529,-0.019477,0.005156,-0.016725,0,0.004444,0.002932,0.005488,0.024441,0.068022,0.609516,80.594574,864.91449,0,0,-0.173257,0.090201,0.334214,-0.059418,-0.001044,-0.021508,0.089533,0.334481,0,144582,146313,146473,144745 -6.031382,-0.021434,0.001432,-0.990393,-0.025863,0.017927,-0.018854,0,-0.001001,-0.000447,-0.002929,0.01755,0.042622,-38.273529,79.666794,627.409851,0,0,-0.17349,0.090327,0.334084,-0.059717,0.001928,-0.017997,0.089533,0.334481,0,144860,146038,146274,144942 -6.036383,-0.029979,-0.011752,-0.992346,-0.020541,0.014734,-0.017789,0,-0.001001,-0.000447,-0.002929,0.01755,0.042622,-32.414577,69.901871,616.548584,0,0,-0.17349,0.090327,0.334084,-0.059717,0.001928,-0.017997,0.089533,0.334481,0,144911,146080,146284,144986 -6.041384,-0.031199,0.000455,-0.992346,-0.019477,0.007285,-0.016725,0,-0.001001,-0.000447,-0.002929,0.01755,0.042622,-18.743692,67.948891,605.687317,0,0,-0.17349,0.090327,0.334084,-0.059717,0.001928,-0.017997,0.089533,0.334481,0,144911,146084,146258,145009 -6.046385,-0.027537,0.003385,-0.995031,-0.016285,0.030697,-0.020982,0,-0.001001,-0.000447,-0.002929,0.01755,0.042622,-61.709335,62.089939,649.132385,0,0,-0.17349,0.090327,0.334084,-0.059717,0.001928,-0.017997,0.089533,0.334481,0,144916,146091,146338,144917 -6.051386,-0.020457,-0.003207,-1.005773,-0.012028,0.011541,-0.020982,0,-0.001001,-0.000447,-0.002929,0.01755,0.042622,-26.555628,54.278004,649.132385,0,0,-0.17349,0.090327,0.334084,-0.059717,0.001928,-0.017997,0.089533,0.334481,0,144889,146134,146295,144944 -6.056387,-0.026805,-0.000766,-0.985754,-0.01522,0.024312,-0.024175,0,-0.001001,-0.000447,-0.002929,0.01755,0.042622,-49.991432,60.136955,681.716248,0,0,-0.17349,0.090327,0.334084,-0.059717,0.001928,-0.017997,0.089533,0.334481,0,145596,146859,147079,145616 -6.061388,-0.027293,-0.009311,-0.988439,-0.006706,0.026441,-0.025239,0,0.003003,0.001712,0.002536,0.025483,0.07488,-43.867306,59.071609,1021.795471,0,0,-0.174592,0.090709,0.33386,-0.059648,0.000467,-0.023771,0.089533,0.334481,0,145251,147206,147412,145281 -6.066389,-0.023875,0.009244,-0.990148,-0.005642,0.015798,-0.026303,0,-0.001739,-0.000312,-0.002279,0.022486,0.053141,-33.173874,51.617897,810.789612,0,0,-0.174499,0.090661,0.333839,-0.059734,0.00054,-0.022798,0.089533,0.334481,0,145458,147013,147183,145495 -6.07139,-0.023143,0.010709,-0.98673,-0.00245,0.038147,-0.03056,0,-0.001739,-0.000312,-0.002279,0.022486,0.053141,-74.186531,45.758945,854.23468,0,0,-0.174499,0.090661,0.333839,-0.059734,0.00054,-0.022798,0.089533,0.334481,0,145462,147022,147262,145405 -6.076391,-0.026805,-0.003695,-0.990393,0.003936,0.020055,-0.03056,0,-0.001739,-0.000312,-0.002279,0.022486,0.053141,-40.985809,34.041042,854.23468,0,0,-0.174499,0.090661,0.333839,-0.059734,0.00054,-0.022798,0.089533,0.334481,0,145440,147067,147217,145426 -6.081392,-0.034373,0.002164,-0.974768,0.001807,0.03389,-0.031624,0,-0.001739,-0.000312,-0.002279,0.022486,0.053141,-66.374596,37.94701,865.095947,0,0,-0.174499,0.090661,0.333839,-0.059734,0.00054,-0.022798,0.089533,0.334481,0,145779,147376,147585,145722 -6.086393,-0.032176,-0.009555,-0.985266,0.008193,0.032826,-0.03056,0,-0.001739,-0.000312,-0.002279,0.022486,0.053141,-64.421616,26.229107,854.23468,0,0,-0.174499,0.090661,0.333839,-0.059734,0.00054,-0.022798,0.089533,0.334481,0,145799,147379,147560,145723 -6.091394,-0.026561,0.009977,-0.98551,0.01245,0.023248,-0.029496,0,-0.001739,-0.000312,-0.002279,0.022486,0.053141,-46.844757,18.417173,843.373413,0,0,-0.174499,0.090661,0.333839,-0.059734,0.00054,-0.022798,0.089533,0.334481,0,145801,147394,147524,145744 -6.096395,-0.026316,0.010465,-0.990148,0.011385,0.034954,-0.029496,0,-0.001739,-0.000312,-0.002279,0.022486,0.053141,-68.327576,20.370157,843.373413,0,0,-0.174499,0.090661,0.333839,-0.059734,0.00054,-0.022798,0.089533,0.334481,0,145820,147370,147548,145724 -6.101397,-0.022898,-0.006625,-1.000891,0.017771,0.015798,-0.028432,0,0.002456,0.000929,-0.002635,0.019303,0.093329,-33.828053,2.811777,1242.667358,0,0,-0.176077,0.091189,0.333603,-0.060005,0.005092,-0.018374,0.089533,0.334481,0,145745,148163,148236,145683 -6.106398,-0.030467,0.004361,-0.98673,0.006064,0.020055,-0.027367,0,0.002456,0.000929,-0.002635,0.019303,0.093329,-41.639988,24.2946,1231.806152,0,0,-0.176077,0.091189,0.333603,-0.060005,0.005092,-0.018374,0.089533,0.334481,0,145742,148122,148254,145707 -6.111399,-0.032908,-0.006381,-0.988928,0.015642,0.016863,-0.025239,0,-0.001547,-0.000624,-0.00715,0.016888,0.081196,-44.065308,2.286665,1086.250854,0,0,-0.176083,0.091141,0.333625,-0.060079,0.005602,-0.017512,0.089533,0.334481,0,145912,147996,148089,145828 -6.1164,-0.027293,0.010465,-0.984045,0.014578,0.004092,-0.020982,0,-0.001547,-0.000624,-0.00715,0.016888,0.081196,-20.629505,4.239647,1042.805786,0,0,-0.176083,0.091141,0.333625,-0.060079,0.005602,-0.017512,0.089533,0.334481,0,145930,147974,148024,145897 -6.121401,-0.01826,0.00485,-0.987463,0.014578,0.016863,-0.020982,0,-0.001547,-0.000624,-0.00715,0.016888,0.081196,-44.065308,4.239647,1042.805786,0,0,-0.176083,0.091141,0.333625,-0.060079,0.005602,-0.017512,0.089533,0.334481,0,146921,148918,149015,146841 -6.126402,-0.016795,-0.01102,-1.002355,0.011385,-0.00655,-0.018854,0,-0.001547,-0.000624,-0.00715,0.016888,0.081196,-1.099668,10.098599,1021.083252,0,0,-0.176083,0.091141,0.333625,-0.060079,0.005602,-0.017512,0.089533,0.334481,0,146893,148933,148956,146911 -6.131403,-0.024607,0.005094,-0.98673,-0.000321,0.007285,-0.014597,0,-0.001547,-0.000624,-0.00715,0.016888,0.081196,-26.488457,31.581421,977.638123,0,0,-0.176083,0.091141,0.333625,-0.060079,0.005602,-0.017512,0.089533,0.334481,0,146941,148843,148959,146951 -6.136404,-0.024852,-0.008334,-0.987463,0.005,0.000899,-0.013532,0,-0.001547,-0.000624,-0.00715,0.016888,0.081196,-14.770554,21.816502,966.776855,0,0,-0.176083,0.091141,0.333625,-0.060079,0.005602,-0.017512,0.089533,0.334481,0,146950,148854,148927,146964 -6.141405,-0.018992,0.010953,-0.981115,0.001807,-0.003358,-0.008211,0,0.000576,-0.000372,-0.004892,0.016948,0.080718,-2.815561,27.785381,907.591797,0,0,-0.176077,0.091142,0.333668,-0.060127,0.005468,-0.017321,0.089533,0.334481,0,146991,148800,148862,147041 -6.146406,-0.009471,-0.003451,-0.981848,-0.000321,-0.000165,-0.01034,0,-0.001597,-0.001354,-0.003587,0.017327,0.07071,-6.280517,32.386898,827.17749,0,0,-0.175753,0.09094,0.333883,-0.060312,0.00199,-0.018681,0.089533,0.334481,0,147997,149639,149716,148049 -6.151407,-0.022166,-0.015902,-0.987707,0.001807,-0.011872,-0.009276,0,0.004248,0.002616,-0.000749,0.019426,0.107075,20.410938,32.332489,1187.450562,0,0,-0.176415,0.091205,0.333729,-0.060285,0.004997,-0.01681,0.089533,0.334481,0,147610,150026,150050,147716 -6.156408,-0.027293,0.00485,-0.987707,-0.010963,-0.000165,-0.006083,0,0.004248,0.002616,-0.000749,0.019426,0.107075,-1.071884,55.768295,1154.866699,0,0,-0.176415,0.091205,0.333729,-0.060285,0.004997,-0.01681,0.089533,0.334481,0,147641,149949,150062,147750 -6.161409,-0.015818,-0.014193,-0.997229,0.001807,-0.008679,-0.008211,0,0.004248,0.002616,-0.000749,0.019426,0.107075,14.551986,32.332489,1176.589233,0,0,-0.176415,0.091205,0.333729,-0.060285,0.004997,-0.01681,0.089533,0.334481,0,147627,150009,150045,147721 -6.16641,-0.011424,0.009,-0.985754,-0.010963,-0.015064,-0.003954,0,0.004248,0.002616,-0.000749,0.019426,0.107075,26.26989,55.768295,1133.144165,0,0,-0.176415,0.091205,0.333729,-0.060285,0.004997,-0.01681,0.089533,0.334481,0,148459,150778,150837,148623 -6.171412,-0.010936,-0.006381,-0.986242,-0.004578,-0.02145,-0.007147,0,0.004248,0.002616,-0.000749,0.019426,0.107075,37.987789,44.050392,1165.728027,0,0,-0.176415,0.091205,0.333729,-0.060285,0.004997,-0.01681,0.089533,0.334481,0,148427,150834,150846,148591 -6.176413,-0.024607,-0.016146,-0.985754,-0.003514,-0.027835,-0.003954,0,0.004248,0.002616,-0.000749,0.019426,0.107075,49.705696,42.097408,1133.144165,0,0,-0.176415,0.091205,0.333729,-0.060285,0.004997,-0.01681,0.089533,0.334481,0,148450,150815,150800,148633 -6.181414,-0.030467,-0.003451,-0.99259,-0.01522,-0.019321,0.001367,0,0.004248,0.002616,-0.000749,0.019426,0.107075,34.081825,63.580231,1078.837769,0,0,-0.176415,0.091205,0.333729,-0.060285,0.004997,-0.01681,0.089533,0.334481,0,148498,150724,150783,148693 -6.186415,-0.011668,-0.0181,-1.007727,-0.00245,-0.036349,0.001367,0,-0.001855,-0.001347,-0.004021,0.017551,0.08568,59.325954,36.702892,860.48407,0,0,-0.176394,0.091131,0.333819,-0.060487,0.002166,-0.018897,0.089533,0.334481,0,148718,150558,150512,148910 -6.191416,-0.009471,0.010465,-1.000891,-0.026927,-0.03422,0.003495,0,0.004825,0.001974,0.00231,0.022339,0.121766,67.038261,90.40786,1207.045166,0,0,-0.177153,0.091431,0.333711,-0.060474,0.002515,-0.020364,0.089533,0.334481,0,148530,151078,151125,148845 -6.196417,-0.009715,-0.006381,-1.001623,-0.020541,-0.050184,0.003495,0,0.004825,0.001974,0.00231,0.022339,0.121766,96.333023,78.689957,1207.045166,0,0,-0.177153,0.091431,0.333711,-0.060474,0.002515,-0.020364,0.089533,0.334481,0,148512,151119,151084,148862 -6.201418,-0.027781,-0.012484,-0.994299,-0.029055,-0.051248,0.007752,0,0.004825,0.001974,0.00231,0.022339,0.121766,98.286011,94.31382,1163.600098,0,0,-0.177153,0.091431,0.333711,-0.060474,0.002515,-0.020364,0.089533,0.334481,0,148538,151062,151054,148923 -6.206419,-0.033885,-0.014193,-0.995275,-0.038633,-0.046991,0.009881,0,0.004825,0.001974,0.00231,0.022339,0.121766,90.474075,111.890678,1141.877441,0,0,-0.177153,0.091431,0.333711,-0.060474,0.002515,-0.020364,0.089533,0.334481,0,148550,151015,151058,148955 -6.21142,-0.020457,-0.02225,-1.0026,-0.031184,-0.058697,0.008816,0,0.004825,0.001974,0.00231,0.022339,0.121766,111.956894,98.219795,1152.73877,0,0,-0.177153,0.091431,0.333711,-0.060474,0.002515,-0.020364,0.089533,0.334481,0,148533,151062,151035,148953 -6.216421,-0.015818,0.000699,-1.011633,-0.057789,-0.046991,0.013073,0,0.004825,0.001974,0.00231,0.022339,0.121766,90.474075,147.044388,1109.293701,0,0,-0.177153,0.091431,0.333711,-0.060474,0.002515,-0.020364,0.089533,0.334481,0,148549,150948,151061,149024 -6.221422,-0.008006,-0.018344,-1.026525,-0.056725,-0.074661,0.007752,0,-0.003693,-0.00199,-0.004018,0.016954,0.064709,129.638046,135.209686,581.292358,0,0,-0.176101,0.091146,0.333897,-0.06064,0.000325,-0.018944,0.089533,0.334481,0,149049,150471,150482,149579 -6.226423,-0.023631,-0.01224,-1.009436,-0.07801,-0.058697,0.009881,0,0.001808,0.001069,0.001541,0.022217,0.081587,110.545235,183.928345,731.822632,0,0,-0.176107,0.091181,0.333872,-0.060646,0.000266,-0.021149,0.089533,0.334481,0,148869,150554,150701,149458 -6.231424,-0.033641,-0.00809,-1.009191,-0.084395,-0.068276,0.009881,0,0.001808,0.001069,0.001541,0.022217,0.081587,128.122086,195.646255,731.822632,0,0,-0.176107,0.091181,0.333872,-0.060646,0.000266,-0.021149,0.089533,0.334481,0,148842,150562,150697,149489 -6.236425,-0.026316,-0.014926,-1.001867,-0.081202,-0.062954,0.005624,0,0.001808,0.001069,0.001541,0.022217,0.081587,118.35717,189.787292,775.2677,0,0,-0.176107,0.091181,0.333872,-0.060646,0.000266,-0.021149,0.089533,0.334481,0,148814,150601,150744,149430 -6.241426,-0.02241,-0.002719,-1.007238,-0.101423,-0.055505,0.006688,0,0.001808,0.001069,0.001541,0.022217,0.081587,104.686279,226.893997,764.406433,0,0,-0.176107,0.091181,0.333872,-0.060646,0.000266,-0.021149,0.089533,0.334481,0,148802,150540,150784,149465 -6.246428,-0.009959,-0.015414,-1.0109,-0.086523,-0.066147,0.003495,0,0.001808,0.001069,0.001541,0.022217,0.081587,124.21611,199.552216,796.990234,0,0,-0.176107,0.091181,0.333872,-0.060646,0.000266,-0.021149,0.089533,0.334481,0,148777,150619,150770,149424 -6.251429,-0.027049,-0.012973,-1.0026,-0.114193,-0.046991,0.002431,0,0.001808,0.001069,0.001541,0.022217,0.081587,89.062408,250.329788,807.851501,0,0,-0.176107,0.091181,0.333872,-0.060646,0.000266,-0.021149,0.089533,0.334481,0,148750,150544,150867,149429 -6.25643,-0.031443,-0.014926,-1.006506,-0.117386,-0.067211,-0.001826,0,0.001808,0.001069,0.001541,0.022217,0.081587,126.169098,256.188751,851.296631,0,0,-0.176107,0.091181,0.333872,-0.060646,0.000266,-0.021149,0.089533,0.334481,0,148674,150629,150889,149439 -6.261431,-0.040721,-0.018344,-0.995275,-0.132285,-0.048055,-0.005019,0,-0.003171,-0.00027,-0.00233,0.020998,0.05433,83.910912,281.293518,605.704407,0,0,-0.175535,0.090998,0.333864,-0.060805,-0.000841,-0.021268,0.089533,0.334481,0,148937,150316,150711,149667 -6.266432,-0.028758,-0.00223,-0.997473,-0.136542,-0.054441,-0.008211,0,0.002126,0.00172,0.004467,0.026495,0.082964,108.102852,299.193512,930.517822,0,0,-0.175938,0.091212,0.333512,-0.061288,-0.002341,-0.024775,0.089533,0.334481,0,148570,150647,151029,149384 -6.271433,-0.017039,-0.009066,-0.994543,-0.128028,-0.054441,-0.012468,0,0.002126,0.00172,0.004467,0.026495,0.082964,108.102852,283.569641,973.962952,0,0,-0.175938,0.091212,0.333512,-0.061288,-0.002341,-0.024775,0.089533,0.334481,0,148542,150706,151057,149325 -6.276434,-0.018016,-0.010531,-0.998449,-0.13867,-0.052312,-0.012468,0,0.002126,0.00172,0.004467,0.026495,0.082964,104.196884,303.099487,973.962952,0,0,-0.175938,0.091212,0.333512,-0.061288,-0.002341,-0.024775,0.089533,0.334481,0,149108,151265,151662,149923 -6.281435,-0.02241,-0.011752,-0.995275,-0.133349,-0.079982,-0.017789,0,0.002126,0.00172,0.004467,0.026495,0.082964,154.974472,293.334564,1028.269287,0,0,-0.175938,0.091212,0.333512,-0.061288,-0.002341,-0.024775,0.089533,0.334481,0,149013,151379,151656,149910 -6.286436,-0.041453,-0.016391,-0.993811,-0.147184,-0.065083,-0.019918,0,0.002126,0.00172,0.004467,0.026495,0.082964,127.632698,318.723358,1049.991821,0,0,-0.175938,0.091212,0.333512,-0.061288,-0.002341,-0.024775,0.089533,0.334481,0,148993,151348,151731,149886 -6.291437,-0.032908,-0.000033,-1.002111,-0.145056,-0.092753,-0.025239,0,0.002126,0.00172,0.004467,0.026495,0.082964,178.410263,314.817383,1104.298218,0,0,-0.175938,0.091212,0.333512,-0.061288,-0.002341,-0.024775,0.089533,0.334481,0,148892,151457,151730,149878 -6.296438,-0.030467,-0.004672,-0.998693,-0.150377,-0.074661,-0.027367,0,0.003481,0.004081,0.009641,0.026255,0.141511,154.704178,324.140442,1723.539917,0,0,-0.178331,0.09213,0.332496,-0.062052,-0.00616,-0.022173,0.089533,0.334481,0,148287,152044,152382,149245 -6.301439,-0.011668,-0.001742,-1.004309,-0.157827,-0.095945,-0.026303,0,0.00439,0.004135,0.011777,0.028141,0.16461,197.68364,341.272278,1948.421997,0,0,-0.179351,0.092536,0.332093,-0.062224,-0.007387,-0.024006,0.089533,0.334481,0,148977,153269,153557,150055 -6.30644,-0.018504,-0.001498,-0.996984,-0.157827,-0.105523,-0.032688,0,0.00439,0.004135,0.011777,0.028141,0.16461,215.260483,341.272278,2013.589722,0,0,-0.179351,0.092536,0.332093,-0.062224,-0.007387,-0.024006,0.089533,0.334481,0,148894,153352,153604,150007 -6.311441,-0.024852,-0.010287,-1.003576,-0.168469,-0.095945,-0.031624,0,0.164289,0.093666,0.208444,0.068839,1.798129,558.591187,435.488098,18674.09375,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,131796,170262,170015,133784 -6.316442,-0.035594,-0.013217,-0.994055,-0.17379,-0.124679,-0.034817,0,0.164289,0.093666,0.208444,0.068839,1.798129,611.321777,445.253021,18706.67773,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,131701,170337,170005,133814 -6.321444,-0.036082,-0.0181,-0.995764,-0.181239,-0.105523,-0.035881,0,0.164289,0.093666,0.208444,0.068839,1.798129,576.16803,458.92392,18717.53906,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132382,170969,170735,134452 -6.326445,-0.023631,-0.004672,-1.007727,-0.192946,-0.142771,-0.024175,0,0.164289,0.093666,0.208444,0.068839,1.798129,644.522461,480.406708,18598.06445,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132412,170897,170568,134661 -6.331446,-0.028514,-0.006137,-1.014318,-0.192946,-0.120423,-0.013532,0,0.164289,0.093666,0.208444,0.068839,1.798129,603.509827,480.406708,18489.45117,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132561,170747,170501,134729 -6.336447,-0.018504,-0.002719,-1.027502,-0.200396,-0.141707,0.004559,0,0.164289,0.093666,0.208444,0.068839,1.798129,642.569519,494.077606,18304.81055,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,132693,170588,170291,134966 -6.341448,-0.034129,-0.004184,-1.035803,-0.203588,-0.140643,0.019459,0,0.164289,0.093666,0.208444,0.068839,1.798129,640.616516,499.936554,18152.75195,0,0,-0.214608,0.104514,0.325222,-0.064556,-0.044154,0.024827,0.089533,0.334481,0,133681,171268,170987,135962 -6.346449,-0.026072,-0.009799,-1.050207,-0.200396,-0.138514,0.040743,0,-0.221409,-0.122364,-0.211557,-0.097072,-0.963148,-134.041611,189.611008,-10245.51367,0,0,-0.179668,0.092758,0.331645,-0.062624,-0.009852,-0.025292,0.089533,0.334481,0,163164,142405,143053,163276 -6.35145,-0.036326,-0.002963,-1.056555,-0.19401,-0.152349,0.055642,0,0.074765,0.045207,0.080767,0.080169,0.04503,427.796539,503.15152,-108.308807,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152152,152791,152942,154014 -6.356451,-0.029979,-0.004916,-1.060705,-0.178047,-0.13745,0.073734,0,0.074765,0.045207,0.080767,0.080169,0.04503,400.454773,473.856781,-292.950409,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152393,152608,152755,154142 -6.361452,-0.034861,0.00485,-1.056066,-0.169533,-0.141707,0.083312,0,0.074765,0.045207,0.080767,0.080169,0.04503,408.266724,458.23288,-390.701904,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152499,152534,152634,154232 -6.366453,-0.031932,-0.001742,-1.070471,-0.162083,-0.1449,0.088633,0,0.074765,0.045207,0.080767,0.080169,0.04503,414.125671,444.562012,-445.008301,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152808,152746,152807,154525 -6.371454,-0.028758,0.003629,-1.069738,-0.151441,-0.138514,0.091826,0,0.074765,0.045207,0.080767,0.080169,0.04503,402.407745,425.032196,-477.592133,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152872,152721,152767,154527 -6.376455,-0.037303,0.00192,-1.069006,-0.148248,-0.141707,0.093954,0,0.074765,0.045207,0.080767,0.080169,0.04503,408.266724,419.173218,-499.314606,0,0,-0.176147,0.09182,0.331322,-0.062934,-0.006001,-0.034961,0.089533,0.334481,0,152893,152711,152733,154548 -6.381456,-0.033641,0.005582,-1.070471,-0.134414,-0.143836,0.091826,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,229.861832,296.212311,-968.647034,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153664,152187,152319,154716 -6.386457,-0.037059,-0.005893,-1.073889,-0.128028,-0.141707,0.09289,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,225.955856,284.494385,-979.50824,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153655,152147,152265,154675 -6.391459,-0.02949,-0.000766,-1.068762,-0.120579,-0.151285,0.085441,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,243.532684,270.823517,-903.47937,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153575,152255,152309,154603 -6.39646,-0.036082,-0.006137,-1.071691,-0.114193,-0.142771,0.082248,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,227.908844,259.105591,-870.895569,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153569,152283,152346,154543 -6.401461,-0.037791,-0.002475,-1.058752,-0.112065,-0.158735,0.07267,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,257.203583,255.199631,-773.144104,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153446,152414,152410,154471 -6.406462,-0.047312,-0.016391,-1.064611,-0.106744,-0.145964,0.067349,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,233.767792,245.434708,-718.837769,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153425,152455,152478,154384 -6.411463,-0.045359,-0.010043,-1.056066,-0.102487,-0.150221,0.063092,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,241.579727,237.622787,-675.392639,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153424,152556,152548,154382 -6.416464,-0.042674,-0.017855,-1.061926,-0.095037,-0.138514,0.054578,0,-0.031394,-0.014263,-0.018579,0.026999,-0.003085,220.096909,223.951889,-588.502441,0,0,-0.172904,0.090803,0.330916,-0.064454,-0.012815,-0.041263,0.089533,0.334481,0,153372,152635,152643,154260 -6.421465,-0.040721,-0.007113,-1.056799,-0.093973,-0.135322,0.047128,0,0.009461,0.009245,0.035455,0.06162,-0.021322,313.395386,285.532745,-698.58728,0,0,-0.170691,0.090296,0.329721,-0.067473,-0.025993,-0.052375,0.089533,0.334481,0,153327,152557,152501,154525 -6.426466,-0.037791,-0.009555,-1.059729,-0.101423,-0.139579,0.036486,0,0.009461,0.009245,0.035455,0.06162,-0.021322,321.207306,299.203644,-589.974548,0,0,-0.170691,0.090296,0.329721,-0.067473,-0.025993,-0.052375,0.089533,0.334481,0,153197,152660,152616,154438 -6.431467,-0.039988,-0.006625,-1.061437,-0.100358,-0.127872,0.027972,0,0.000065,0.005708,0.019697,0.050031,0.028214,270.807312,275.9823,2.464528,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152620,153167,153177,153714 -6.436468,-0.049021,-0.002719,-1.058508,-0.109936,-0.124679,0.023715,0,0.000065,0.005708,0.019697,0.050031,0.028214,264.948364,293.559143,45.909622,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152565,153187,153244,153682 -6.441469,-0.044383,-0.005893,-1.060949,-0.108872,-0.118294,0.01733,0,0.000065,0.005708,0.019697,0.050031,0.028214,253.230469,291.606171,111.077271,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152514,153242,153319,153603 -6.44647,-0.051951,0.000455,-1.065832,-0.120579,-0.100202,0.012009,0,0.000065,0.005708,0.019697,0.050031,0.028214,220.029739,313.088989,165.383636,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152471,153242,153428,153537 -6.451471,-0.040477,-0.00516,-1.08048,-0.119514,-0.092753,0.002431,0,0.000065,0.005708,0.019697,0.050031,0.028214,206.358841,311.136017,263.135101,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152400,153339,153548,153435 -6.456472,-0.044871,-0.001742,-1.072668,-0.120579,-0.075725,-0.003954,0,0.000065,0.005708,0.019697,0.050031,0.028214,175.111115,313.088989,328.302734,0,0,-0.17137,0.090544,0.329071,-0.068452,-0.019632,-0.044323,0.089533,0.334481,0,152364,153371,153647,153340 -6.461473,-0.036814,0.000943,-1.078771,-0.128028,-0.076789,-0.011404,0,-0.001065,0.004985,0.022011,0.050641,-0.005194,181.309982,327.879913,63.379238,0,0,-0.170989,0.090393,0.32806,-0.070697,-0.023076,-0.045656,0.089533,0.334481,0,152608,153097,153390,153626 -6.466475,-0.040965,0.000943,-1.066564,-0.124836,-0.065083,-0.019918,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,159.491013,329.699799,-109.653984,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152801,152901,153241,153779 -6.471476,-0.043162,-0.007357,-1.068518,-0.135478,-0.060826,-0.026303,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,151.679077,349.229645,-44.486332,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152724,152938,153334,153726 -6.476477,-0.046092,-0.003695,-1.051428,-0.132285,-0.053376,-0.033753,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,138.008179,343.370697,31.542593,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152706,153045,153455,153668 -6.481478,-0.047557,-0.010043,-1.046301,-0.133349,-0.055505,-0.036945,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,141.914154,345.3237,64.126389,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152667,153079,153486,153642 -6.486479,-0.037547,0.001187,-1.041906,-0.130157,-0.054441,-0.045459,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,139.961166,339.464722,151.016571,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152588,153170,153569,153547 -6.49148,-0.042186,-0.007357,-1.054357,-0.126964,-0.06189,-0.047588,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,153.63205,333.605774,172.73912,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152559,153211,153571,153533 -6.496481,-0.034861,0.004361,-1.053137,-0.126964,-0.072532,-0.056101,0,-0.003583,0.003164,0.021827,0.054825,-0.030662,173.161896,333.605774,259.629303,0,0,-0.170323,0.090107,0.327704,-0.071838,-0.025411,-0.051662,0.089533,0.334481,0,152472,153338,153659,153486 -6.501482,-0.038035,0.003141,-1.043127,-0.122707,-0.081046,-0.061423,0,0.005803,0.011575,0.0352,0.069559,0.084575,213.3255,352.831543,1490.022461,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,151182,154589,154868,152315 -6.506483,-0.035838,0.010709,-1.046789,-0.130157,-0.093817,-0.066744,0,0.005803,0.011575,0.0352,0.069559,0.084575,236.761292,366.502441,1544.328857,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,151091,154653,154913,152297 -6.511484,-0.039012,0.009488,-1.04923,-0.126964,-0.095945,-0.073129,0,0.005803,0.011575,0.0352,0.069559,0.084575,240.667267,360.643463,1609.49646,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,151028,154728,154968,152230 -6.516485,-0.0395,0.007047,-1.04923,-0.133349,-0.102331,-0.076322,0,0.005803,0.011575,0.0352,0.069559,0.084575,252.385178,372.361389,1642.080322,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150972,154761,155001,152221 -6.521486,-0.039988,0.010465,-1.030676,-0.128028,-0.102331,-0.082707,0,0.005803,0.011575,0.0352,0.069559,0.084575,252.385178,362.596466,1707.247925,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150843,154763,154983,152073 -6.526487,-0.036814,0.00192,-1.027746,-0.1259,-0.107652,-0.081643,0,0.005803,0.011575,0.0352,0.069559,0.084575,262.150085,358.690491,1696.386597,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150848,154765,154958,152090 -6.531488,-0.026316,0.007535,-1.025549,-0.128028,-0.112973,-0.086964,0,0.005803,0.011575,0.0352,0.069559,0.084575,271.915009,362.596466,1750.692993,0,0,-0.174314,0.091412,0.324042,-0.077342,-0.029396,-0.057984,0.089533,0.334481,0,150780,154826,155007,152049 -6.536489,-0.029246,-0.008822,-1.033605,-0.119514,-0.121487,-0.089092,0,0.005414,0.011035,0.034504,0.069701,0.166096,286.262482,347.233307,2604.397705,0,0,-0.178617,0.093033,0.320763,-0.081838,-0.02909,-0.058666,0.089533,0.334481,0,149928,155709,155831,151195 -6.541491,-0.033641,0.002164,-1.006262,-0.11845,-0.127872,-0.091221,0,0.000548,0.009802,0.035223,0.071678,0.133144,299.299255,348.908173,2289.823975,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150286,155465,155564,151583 -6.546492,-0.030955,-0.009799,-1.004553,-0.109936,-0.141707,-0.092285,0,0.000548,0.009802,0.035223,0.071678,0.133144,324.688049,333.284302,2300.685303,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150266,155517,155534,151582 -6.551493,-0.038035,-0.005893,-1.004797,-0.111001,-0.149157,-0.090157,0,0.000548,0.009802,0.035223,0.071678,0.133144,338.358948,335.237274,2278.962646,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150272,155507,155500,151619 -6.556494,-0.028758,-0.007113,-1.008703,-0.106744,-0.162992,-0.094414,0,0.000548,0.009802,0.035223,0.071678,0.133144,363.747711,327.425354,2322.407959,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150211,155583,155511,151593 -6.561495,-0.035105,-0.001254,-0.99552,-0.105679,-0.174698,-0.094414,0,0.000548,0.009802,0.035223,0.071678,0.133144,385.23056,325.472351,2322.407959,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150187,155603,155483,151609 -6.566496,-0.026805,0.003141,-0.992834,-0.09823,-0.186405,-0.096542,0,0.000548,0.009802,0.035223,0.071678,0.133144,406.713379,311.801483,2344.130371,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150158,155660,155470,151595 -6.571497,-0.027049,0.004361,-0.988684,-0.095037,-0.200239,-0.094414,0,0.000548,0.009802,0.035223,0.071678,0.133144,432.102142,305.942535,2322.407959,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150160,155669,155417,151636 -6.576498,-0.027537,0.006559,-0.992834,-0.089716,-0.208753,-0.096542,0,0.000548,0.009802,0.035223,0.071678,0.133144,447.726013,296.177612,2344.130371,0,0,-0.178876,0.093211,0.319774,-0.083455,-0.034675,-0.061876,0.089533,0.334481,0,150132,155716,155413,151620 -6.581499,-0.019969,0.003141,-0.99259,-0.093973,-0.226845,-0.096542,0,0.00944,0.014183,0.046678,0.080704,0.234826,501.948853,320.55368,3381.871826,0,0,-0.182364,0.094601,0.317227,-0.086471,-0.037239,-0.066521,0.089533,0.334481,0,149016,156784,156421,150661 -6.5865,-0.037303,-0.003939,-0.983557,-0.097166,-0.232166,-0.099735,0,0.002105,0.01083,0.043179,0.075637,0.213407,505.291534,317.114746,3195.86377,0,0,-0.183428,0.09539,0.314939,-0.089857,-0.041074,-0.064807,0.089533,0.334481,0,149166,156569,156192,150811 -6.591501,-0.025096,0.00485,-0.985021,-0.101423,-0.251322,-0.100799,0,-0.002989,0.008261,0.042601,0.07447,0.141009,539.385376,322.783813,2467.846191,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149854,155869,155436,151579 -6.596502,-0.04658,-0.001742,-0.969641,-0.105679,-0.253451,-0.096542,0,-0.002989,0.008261,0.042601,0.07447,0.141009,543.291321,330.595734,2424.401123,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149886,155822,155396,151634 -6.601503,-0.023631,0.004117,-0.987707,-0.115257,-0.269414,-0.094414,0,-0.002989,0.008261,0.042601,0.07447,0.141009,572.586121,348.172607,2402.678711,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149861,155812,155363,151703 -6.606504,-0.032908,0.007779,-0.968664,-0.1259,-0.269414,-0.090157,0,-0.002989,0.008261,0.042601,0.07447,0.141009,572.586121,367.702423,2359.233643,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149924,155788,155378,151805 -6.611506,-0.024119,-0.001498,-0.977697,-0.137606,-0.278992,-0.086964,0,-0.002989,0.008261,0.042601,0.07447,0.141009,590.162964,389.185272,2326.649658,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149918,155751,155349,151876 -6.616507,-0.02827,0.010465,-0.974035,-0.15357,-0.283249,-0.088028,0,-0.002989,0.008261,0.042601,0.07447,0.141009,597.974915,418.480011,2337.510986,0,0,-0.182251,0.095227,0.314068,-0.091176,-0.04559,-0.066209,0.089533,0.334481,0,149870,155741,155382,151902 -6.621508,-0.037303,-0.018344,-0.983068,-0.159955,-0.280056,-0.083771,0,0.009291,0.01657,0.063571,0.083133,0.245788,630.598633,446.09549,3363.417725,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148783,156771,156402,150937 -6.626509,-0.032664,0.00485,-0.979895,-0.196139,-0.298148,-0.081643,0,0.009291,0.01657,0.063571,0.083133,0.245788,663.799316,512.496948,3341.695312,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148706,156716,156414,151058 -6.63151,-0.041697,-0.014682,-0.971594,-0.190818,-0.286442,-0.080579,0,0.009291,0.01657,0.063571,0.083133,0.245788,642.316467,502.732025,3330.833984,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148705,156651,156372,150995 -6.636511,-0.026805,0.015836,-0.977453,-0.227001,-0.292827,-0.079514,0,0.009291,0.01657,0.063571,0.083133,0.245788,654.034424,569.133484,3319.972656,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148637,156585,156416,151084 -6.641512,-0.03242,0.00607,-0.965002,-0.220616,-0.282185,-0.076322,0,0.009291,0.01657,0.063571,0.083133,0.245788,634.504578,557.415588,3287.388916,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148701,156545,156391,151085 -6.646513,-0.020945,0.006803,-0.977209,-0.24935,-0.283249,-0.073129,0,0.009291,0.01657,0.063571,0.083133,0.245788,636.457581,610.146118,3254.804932,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148679,156462,156409,151172 -6.651514,-0.034617,0.005094,-0.967443,-0.247221,-0.278992,-0.073129,0,0.009291,0.01657,0.063571,0.083133,0.245788,628.64563,606.240173,3254.804932,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148699,156466,156421,151169 -6.656515,-0.037791,-0.016146,-0.971838,-0.261056,-0.263029,-0.069936,0,0.009291,0.01657,0.063571,0.083133,0.245788,599.350891,631.628906,3222.221191,0,0,-0.18483,0.097004,0.309854,-0.095949,-0.05428,-0.066563,0.089533,0.334481,0,148735,156378,156443,151197 -6.661516,-0.043895,0.000455,-0.97843,-0.280212,-0.265157,-0.068872,0,0.001518,0.01505,0.059947,0.084196,0.232589,596.605652,668.733826,3076.653809,0,0,-0.18527,0.097699,0.306837,-0.098775,-0.058429,-0.069146,0.089533,0.334481,0,148847,156193,156337,151377 -6.666517,-0.031199,-0.022738,-0.9755,-0.265313,-0.24813,-0.067808,0,0.009062,0.019296,0.073325,0.094303,0.289687,589.908203,659.939758,3648.523926,0,0,-0.187304,0.099082,0.303287,-0.101578,-0.064263,-0.075007,0.089533,0.334481,0,148290,156767,156907,150790 -6.671518,-0.024363,0.010709,-0.959143,-0.295112,-0.250258,-0.065679,0,-0.00577,0.010068,0.062218,0.085465,0.166748,573.432434,698.404846,2372.109375,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149585,155476,155726,152128 -6.676519,-0.032664,0.011197,-0.952062,-0.285534,-0.249194,-0.063551,0,-0.00577,0.010068,0.062218,0.085465,0.166748,571.479431,680.827942,2350.386963,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149626,155470,155688,152130 -6.68152,-0.034617,0.010221,-0.956457,-0.303625,-0.238552,-0.05823,0,-0.00577,0.010068,0.062218,0.085465,0.166748,551.949585,714.028687,2296.080566,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149666,155363,155687,152198 -6.686522,-0.024119,0.023893,-0.961584,-0.299369,-0.238552,-0.057166,0,-0.00577,0.010068,0.062218,0.085465,0.166748,551.949585,706.216736,2285.219238,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149685,155359,155668,152201 -6.691523,-0.025584,0.012174,-0.959631,-0.303625,-0.228974,-0.055037,0,-0.00577,0.010068,0.062218,0.085465,0.166748,534.372742,714.028687,2263.496826,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149717,155312,155672,152213 -6.696524,-0.023387,0.017301,-0.973791,-0.318525,-0.247065,-0.05078,0,-0.00577,0.010068,0.062218,0.085465,0.166748,567.573486,741.370483,2220.051758,0,0,-0.185379,0.098897,0.302069,-0.103009,-0.067988,-0.075397,0.089533,0.334481,0,149665,155240,155587,152282 -6.701525,-0.044627,0.001432,-0.970617,-0.315332,-0.235359,-0.05078,0,0.01477,0.024073,0.084526,0.103699,0.305827,587.028076,768.973633,3639.465576,0,0,-0.18704,0.099813,0.300079,-0.104311,-0.069756,-0.079627,0.089533,0.334481,0,148198,156651,157015,150910 -6.706526,-0.043895,-0.00101,-0.965246,-0.33236,-0.250258,-0.048652,0,0.01477,0.024073,0.084526,0.103699,0.305827,614.369873,800.221375,3617.74292,0,0,-0.18704,0.099813,0.300079,-0.104311,-0.069756,-0.079627,0.089533,0.334481,0,148161,156625,156997,150990 -6.711527,-0.024852,0.009977,-0.962561,-0.334488,-0.257708,-0.053973,0,0.01477,0.024073,0.084526,0.103699,0.305827,628.04071,804.127319,3672.049316,0,0,-0.18704,0.099813,0.300079,-0.104311,-0.069756,-0.079627,0.089533,0.334481,0,148089,156689,157042,150954 -6.716528,-0.027293,-0.002719,-0.966223,-0.350451,-0.266221,-0.05078,0,0.001642,0.017462,0.083061,0.110254,0.250542,640.975525,845.450562,3075.240234,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148623,156055,156464,151596 -6.721529,-0.015818,0.005094,-0.977697,-0.362158,-0.298148,-0.051845,0,0.001642,0.017462,0.083061,0.110254,0.250542,699.565063,866.933411,3086.101562,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148532,156103,156438,151665 -6.72653,-0.062693,-0.018832,-0.974035,-0.375993,-0.28857,-0.045459,0,0.001642,0.017462,0.083061,0.110254,0.250542,681.988159,892.322205,3020.933838,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148589,155995,156416,151738 -6.731531,-0.036326,-0.005648,-0.977697,-0.40047,-0.327947,-0.041202,0,0.001642,0.017462,0.083061,0.110254,0.250542,754.248596,937.240845,2977.48877,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148516,155979,156345,151899 -6.736532,-0.037547,-0.012973,-0.959631,-0.408984,-0.315176,-0.042266,0,0.001642,0.017462,0.083061,0.110254,0.250542,730.812805,952.864685,2988.350098,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148512,155951,156395,151880 -6.741533,-0.016062,0.003141,-0.969152,-0.431332,-0.34391,-0.036945,0,0.001642,0.017462,0.083061,0.110254,0.250542,783.543335,993.87738,2934.043701,0,0,-0.186927,0.101304,0.294458,-0.108071,-0.081419,-0.092792,0.089533,0.334481,0,148510,155945,156366,152065 -6.746534,-0.023387,0.018277,-0.961096,-0.439846,-0.36413,-0.039074,0,0.016426,0.030313,0.100886,0.125293,0.357282,853.361023,1037.10022,4045.128906,0,0,-0.189161,0.10253,0.291828,-0.109526,-0.084459,-0.09498,0.089533,0.334481,0,147286,157083,157450,151067 -6.751535,-0.045115,-0.007113,-0.953771,-0.463259,-0.369451,-0.034817,0,0.003708,0.019999,0.098309,0.130303,0.285718,858.398193,1089.259399,3271.313965,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,148003,156262,156724,151898 -6.756536,-0.053416,0.01901,-0.946691,-0.487736,-0.394993,-0.033753,0,0.003708,0.019999,0.098309,0.130303,0.285718,905.269836,1134.177979,3260.452637,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147922,156253,156711,152000 -6.761538,-0.054881,-0.009799,-0.948645,-0.48348,-0.387543,-0.032688,0,0.003708,0.019999,0.098309,0.130303,0.285718,891.598938,1126.366089,3249.591309,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147927,156209,156679,151963 -6.766539,-0.042186,0.019986,-0.955236,-0.514342,-0.403507,-0.022046,0,0.003708,0.019999,0.098309,0.130303,0.285718,920.893677,1183.002563,3140.97876,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147950,156073,156598,152157 -6.77154,-0.032176,-0.003207,-0.949621,-0.484544,-0.407763,-0.026303,0,0.003708,0.019999,0.098309,0.130303,0.285718,928.705627,1128.31897,3184.423828,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147953,156179,156579,152067 -6.776541,-0.03242,0.007535,-0.948889,-0.517535,-0.413085,-0.022046,0,0.003708,0.019999,0.098309,0.130303,0.285718,938.47052,1188.861572,3140.97876,0,0,-0.189116,0.104594,0.285181,-0.112792,-0.094602,-0.110304,0.089533,0.334481,0,147926,156085,156586,152181 -6.781542,-0.046336,0.002896,-0.942541,-0.495186,-0.429048,-0.020982,0,0.010053,0.029031,0.117675,0.152133,0.274712,1003.303772,1187.90979,3017.791016,0,0,-0.188678,0.107048,0.27738,-0.115865,-0.107623,-0.123102,0.089533,0.334481,0,147982,156025,156394,152365 -6.786543,-0.04951,-0.002475,-0.939367,-0.514342,-0.427984,-0.017789,0,0.010053,0.029031,0.117675,0.152133,0.274712,1001.350769,1223.063477,2985.207275,0,0,-0.188678,0.107048,0.27738,-0.115865,-0.107623,-0.123102,0.089533,0.334481,0,147982,155955,156398,152431 -6.791544,-0.056102,0.009,-0.935949,-0.499443,-0.435433,-0.015661,0,0.007036,0.02832,0.120421,0.157578,0.272034,1020.060364,1205.712646,2936.161133,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148030,155942,156313,152481 -6.796545,-0.044383,-0.002963,-0.931555,-0.497314,-0.434369,-0.015661,0,0.007036,0.02832,0.120421,0.157578,0.272034,1018.107422,1201.806641,2936.161133,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148035,155944,156311,152475 -6.801546,-0.04658,0.012418,-0.939123,-0.491993,-0.440754,-0.008211,0,0.007036,0.02832,0.120421,0.157578,0.272034,1029.825317,1192.041748,2860.132324,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148110,155889,156214,152553 -6.806547,-0.037059,-0.000521,-0.946203,-0.471773,-0.436498,-0.011404,0,0.007036,0.02832,0.120421,0.157578,0.272034,1022.013367,1154.935181,2892.716064,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148165,155994,156260,152519 -6.811548,-0.04365,0.009488,-0.944494,-0.472837,-0.432241,-0.005019,0,0.007036,0.02832,0.120421,0.157578,0.272034,1014.201416,1156.888062,2827.548584,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148236,155919,156205,152578 -6.816549,-0.041453,0.011686,-0.953771,-0.454745,-0.443947,-0.007147,0,0.007036,0.02832,0.120421,0.157578,0.272034,1035.684204,1123.687378,2849.270996,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148226,155996,156172,152545 -6.82155,-0.042186,0.027066,-0.944982,-0.445167,-0.418406,-0.00289,0,0.007036,0.02832,0.120421,0.157578,0.272034,988.812683,1106.110474,2805.825928,0,0,-0.188524,0.107811,0.274599,-0.116704,-0.113385,-0.129257,0.089533,0.334481,0,148334,155923,156158,152524 -6.826551,-0.038035,0.025846,-0.953527,-0.421754,-0.433305,-0.001826,0,0.009767,0.030146,0.137926,0.172346,0.237777,1048.277588,1090.246216,2445.338379,0,0,-0.187034,0.110458,0.26592,-0.119144,-0.128159,-0.1422,0.089533,0.334481,0,148645,155632,155716,152922 -6.831553,-0.035105,0.031949,-0.944494,-0.404727,-0.409892,-0.000762,0,0.00815,0.030216,0.139942,0.175236,0.206208,1009.01239,1064.303345,2112.29248,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149043,155286,155396,153190 -6.836554,-0.041941,0.021207,-0.95548,-0.378121,-0.421598,0.002431,0,0.00815,0.030216,0.139942,0.175236,0.206208,1030.495239,1015.478699,2079.70874,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149103,155323,155293,153195 -6.841555,-0.051707,0.027311,-0.956213,-0.362158,-0.388607,0.001367,0,0.00815,0.030216,0.139942,0.175236,0.206208,969.952698,986.183899,2090.569824,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149182,155303,155335,153094 -6.846556,-0.047068,0.010221,-0.967443,-0.327038,-0.387543,0.007752,0,0.00815,0.030216,0.139942,0.175236,0.206208,967.999756,921.735474,2025.402222,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149313,155300,155208,153093 -6.851557,-0.048289,0.015348,-0.97135,-0.314268,-0.356681,0.012009,0,0.00815,0.030216,0.139942,0.175236,0.206208,911.36322,898.299683,1981.957153,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149397,155184,155157,153016 -6.856558,-0.039744,0.002164,-0.970373,-0.271699,-0.348167,0.010945,0,0.00815,0.030216,0.139942,0.175236,0.206208,895.73938,820.180298,1992.818481,0,0,-0.186035,0.111294,0.262976,-0.119863,-0.131792,-0.145021,0.089533,0.334481,0,149480,155257,155106,152912 -6.861559,-0.044627,0.00485,-0.968176,-0.268506,-0.32369,0.015202,0,0.014863,0.036434,0.152626,0.181732,0.251648,874.097656,826.241211,2413.12085,0,0,-0.186478,0.113851,0.256189,-0.121182,-0.137764,-0.145298,0.089533,0.334481,0,149075,155649,155554,152476 -6.86656,-0.04365,0.002652,-0.957189,-0.233387,-0.315176,0.014137,0,0.000644,0.026298,0.142909,0.177613,0.083573,840.642029,754.234802,708.641296,0,0,-0.183068,0.114275,0.253368,-0.121638,-0.142265,-0.151315,0.089533,0.334481,0,150885,153984,153811,154075 -6.871561,-0.039988,0.008268,-0.952062,-0.22168,-0.297084,0.016266,0,0.016514,0.039456,0.161102,0.189806,0.175019,840.82782,755.126343,1620.19873,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150615,155537,155366,153807 -6.876562,-0.046336,0.009977,-0.943762,-0.192946,-0.281121,0.013073,0,0.016514,0.039456,0.161102,0.189806,0.175019,811.533081,702.395813,1652.782593,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150665,155593,155375,153693 -6.881563,-0.042186,0.009488,-0.942053,-0.171661,-0.271543,0.015202,0,0.016514,0.039456,0.161102,0.189806,0.175019,793.956238,663.336121,1631.060059,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150743,155593,155332,153658 -6.886564,-0.052684,0.007779,-0.927893,-0.150377,-0.252387,0.015202,0,0.016514,0.039456,0.161102,0.189806,0.175019,758.802551,624.276489,1631.060059,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,150817,155597,155328,153584 -6.891565,-0.043406,0.015592,-0.929846,-0.128028,-0.24813,0.015202,0,0.016514,0.039456,0.161102,0.189806,0.175019,750.990601,583.263794,1631.060059,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,151114,155878,155543,153783 -6.896566,-0.047068,0.014615,-0.928625,-0.109936,-0.216203,0.014137,0,0.016514,0.039456,0.161102,0.189806,0.175019,692.401062,550.063049,1641.921265,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,151195,155864,155579,153680 -6.901567,-0.013377,0.025113,-0.932287,-0.086523,-0.228974,0.008816,0,0.016514,0.039456,0.161102,0.189806,0.175019,715.836853,507.097443,1696.227661,0,0,-0.18273,0.115479,0.249859,-0.122284,-0.144589,-0.15035,0.089533,0.334481,0,151160,155984,155567,153606 -6.906569,-0.031687,0.020963,-0.921301,-0.07056,-0.200239,0.005624,0,0.017936,0.041862,0.165531,0.196339,0.282214,671.233643,489.791321,2822.821045,0,0,-0.186409,0.120623,0.237799,-0.123557,-0.147595,-0.154476,0.089533,0.334481,0,150096,157084,156721,152418 -6.91157,-0.027049,0.025113,-0.925207,-0.05034,-0.21301,0.005624,0,0.009401,0.037501,0.163093,0.200452,0.176709,690.194458,460.232819,1746.067017,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151183,156056,155596,153484 -6.916571,-0.059275,0.020963,-0.919836,-0.040762,-0.194918,0.005624,0,0.009401,0.037501,0.163093,0.200452,0.176709,656.993713,442.655975,1746.067017,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,150996,155802,155373,153195 -6.921572,-0.043406,0.017301,-0.931311,-0.016285,-0.190661,0.001367,0,0.009401,0.037501,0.163093,0.200452,0.176709,649.181824,397.737335,1789.512207,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151005,155882,155380,153099 -6.926573,-0.036326,0.028775,-0.930334,-0.004578,-0.183212,0.000303,0,0.009401,0.037501,0.163093,0.200452,0.176709,635.510925,376.254517,1800.373413,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151029,155901,155383,153053 -6.931574,-0.023631,0.009488,-0.939123,0.030541,-0.175762,0.002431,0,0.009401,0.037501,0.163093,0.200452,0.176709,621.840027,311.806061,1778.650879,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151129,155930,155310,152996 -6.936575,-0.020945,0.028775,-0.9401,0.031606,-0.18534,-0.000762,0,0.009401,0.037501,0.163093,0.200452,0.176709,639.416931,309.853058,1811.234741,0,0,-0.184994,0.121757,0.234033,-0.123702,-0.153692,-0.16295,0.089533,0.334481,0,151293,156194,155535,153192 -6.941576,-0.053416,-0.006625,-0.941076,0.07311,-0.158735,-0.001826,0,0.022522,0.047093,0.173849,0.202117,0.256373,610.332092,236.743118,2635.12793,0,0,-0.186108,0.12548,0.225344,-0.124075,-0.151327,-0.155025,0.089533,0.334481,0,150571,157062,156315,152265 -6.946577,-0.041941,0.013639,-0.945959,0.055019,-0.168313,0.000303,0,0.017676,0.044686,0.170953,0.197885,0.219845,622.593994,262.177338,2240.607178,0,0,-0.185706,0.127329,0.220928,-0.124114,-0.153277,-0.153199,0.089533,0.334481,0,150928,156655,155934,152698 -6.951578,-0.048533,-0.010287,-0.932531,0.10078,-0.141707,-0.008211,0,0.017349,0.045638,0.171588,0.197305,0.195062,574.934082,177.13472,2074.563721,0,0,-0.184913,0.129029,0.216505,-0.124139,-0.154239,-0.151667,0.089533,0.334481,0,151227,156526,155730,152731 -6.956579,-0.019725,0.015592,-0.940588,0.082688,-0.13745,-0.006083,0,0.017349,0.045638,0.171588,0.197305,0.195062,567.122131,210.335464,2052.841309,0,0,-0.184913,0.129029,0.216505,-0.124139,-0.154239,-0.151667,0.089533,0.334481,0,151223,156463,155750,152778 -6.96158,-0.02241,0.009488,-0.93009,0.112487,-0.131065,-0.011404,0,0.018582,0.047641,0.176735,0.199822,0.17726,564.85083,160.270859,1925.462402,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151410,156391,155581,152860 -6.966581,-0.025096,-0.004428,-0.938146,0.101845,-0.123615,-0.008211,0,0.018582,0.047641,0.176735,0.199822,0.17726,551.179932,179.800705,1892.87854,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151437,156325,155582,152899 -6.971582,-0.051951,0.012418,-0.928869,0.106101,-0.108716,-0.008211,0,0.018582,0.047641,0.176735,0.199822,0.17726,523.838196,171.98877,1892.87854,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151472,156305,155602,152863 -6.976583,-0.047801,-0.01932,-0.929357,0.123129,-0.085303,-0.01034,0,0.018582,0.047641,0.176735,0.199822,0.17726,480.872528,140.741028,1914.601074,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151524,156315,155635,152768 -6.981585,-0.04243,0.017545,-0.927648,0.099716,-0.073597,-0.009276,0,0.018582,0.047641,0.176735,0.199822,0.17726,459.389709,183.706665,1903.739868,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151622,156348,155797,152908 -6.986586,-0.027537,-0.008334,-0.929846,0.139092,-0.053376,-0.013532,0,0.018582,0.047641,0.176735,0.199822,0.17726,422.28302,111.446259,1947.184937,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151688,156427,155805,152755 -6.991587,-0.026316,0.022916,-0.936926,0.103973,-0.049119,-0.007147,0,0.018582,0.047641,0.176735,0.199822,0.17726,414.471069,175.89473,1882.017334,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151696,156289,155812,152877 -6.996588,-0.021922,0.006559,-0.931799,0.143349,-0.03422,-0.013532,0,0.018582,0.047641,0.176735,0.199822,0.17726,387.129303,103.634315,1947.184937,0,0,-0.184008,0.13081,0.211915,-0.123964,-0.158153,-0.152181,0.089533,0.334481,0,151731,156399,155832,152712 -7.001589,-0.034129,0.000699,-0.926184,0.116744,-0.015064,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,361.496948,153.802368,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151377,156856,156441,152408 -7.00659,-0.043406,0.004605,-0.932287,0.142285,-0.012936,-0.013532,0,0.023289,0.054334,0.181924,0.200554,0.223726,357.590973,106.930756,2421.416016,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151385,156943,156441,152314 -7.011591,-0.051463,-0.008822,-0.937414,0.130579,0.015798,-0.011404,0,0.023289,0.054334,0.181924,0.200554,0.223726,304.860413,128.413589,2399.693359,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151438,156847,156494,152304 -7.016592,-0.042918,-0.002475,-0.942053,0.139092,0.010477,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,314.625336,112.789703,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151465,156850,156447,152320 -7.021593,-0.041453,-0.012484,-0.936682,0.138028,0.039211,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,261.894775,114.742691,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151516,156796,156501,152269 -7.026594,-0.030467,-0.007602,-0.948645,0.132707,0.026441,-0.009276,0,0.023289,0.054334,0.181924,0.200554,0.223726,285.330597,124.507614,2377.970947,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151382,156708,156387,152201 -7.031595,-0.028514,-0.01102,-0.946203,0.139092,0.042404,-0.014597,0,0.023289,0.054334,0.181924,0.200554,0.223726,256.035828,112.789703,2432.277344,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151368,156745,156459,152106 -7.036596,-0.034861,-0.011996,-0.951574,0.124193,0.040276,-0.008211,0,0.023289,0.054334,0.181924,0.200554,0.223726,259.941803,140.131485,2367.109619,0,0,-0.184768,0.139412,0.191427,-0.122792,-0.158635,-0.14622,0.089533,0.334481,0,151402,156656,156417,152202 -7.041597,-0.028514,-0.00101,-0.962316,0.115679,0.028569,-0.009276,0,0.028358,0.062464,0.186246,0.202401,0.31936,289.356995,159.144669,3353.991211,0,0,-0.187995,0.144686,0.17967,-0.12193,-0.157888,-0.139938,0.089533,0.334481,0,150367,157654,157393,151264 -7.046598,-0.041941,-0.009799,-0.95133,0.10078,0.049854,-0.005019,0,0.023663,0.056983,0.181776,0.196189,0.239166,242.093414,175.087311,2492.101807,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151262,156731,156597,152097 -7.0516,-0.033396,0.010221,-0.959875,0.081624,0.027505,-0.005019,0,0.023663,0.056983,0.181776,0.196189,0.239166,283.106079,210.241013,2492.101807,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151186,156736,156591,152173 -7.056601,-0.04243,0.001187,-0.954748,0.079496,0.05411,-0.00289,0,0.023663,0.056983,0.181776,0.196189,0.239166,234.281479,214.146988,2470.379395,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151253,156662,156622,152150 -7.061602,-0.02241,0.009732,-0.962561,0.06034,0.029633,-0.001826,0,0.023663,0.056983,0.181776,0.196189,0.239166,279.200104,249.30069,2459.518066,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151183,156661,156601,152240 -7.066603,-0.03657,0.011197,-0.955725,0.055019,0.053046,-0.000762,0,0.023663,0.056983,0.181776,0.196189,0.239166,236.234467,259.065613,2448.656738,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151228,156597,156643,152218 -7.071604,-0.027781,0.004361,-0.95841,0.041184,0.027505,0.002431,0,0.023663,0.056983,0.181776,0.196189,0.239166,283.106079,284.454407,2416.072998,0,0,-0.187062,0.14954,0.168291,-0.120625,-0.158113,-0.139206,0.089533,0.334481,0,151298,156696,156699,152433 -7.076605,-0.042674,0.01315,-0.948889,0.033734,0.042404,-0.000762,0,0.029308,0.067461,0.18471,0.206612,0.305971,261.148407,317.252167,3130.456787,0,0,-0.188165,0.152253,0.161987,-0.119807,-0.155402,-0.139151,0.089533,0.334481,0,150573,157356,157468,151729 -7.081606,-0.038279,-0.000766,-0.949133,0.033734,0.032826,0.003495,0,0.025529,0.06212,0.180739,0.20275,0.25357,271.437866,310.165466,2552.217529,0,0,-0.187791,0.154838,0.155801,-0.119053,-0.155209,-0.14063,0.089533,0.334481,0,151148,156795,156872,152311 -7.086607,-0.037791,0.017301,-0.944494,0.010321,0.022184,0.001367,0,0.031373,0.067916,0.182624,0.202434,0.288092,294.427826,352.551117,2926.263428,0,0,-0.188514,0.160656,0.142871,-0.117538,-0.151251,-0.134519,0.089533,0.334481,0,150708,157150,157266,152002 -7.091608,-0.034861,-0.001254,-0.948156,0.028413,0.030697,0.003495,0,0.02954,0.068626,0.180453,0.203518,0.281601,274.820435,321.339905,2838.296631,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150731,156957,157050,151923 -7.096609,-0.034129,0.008512,-0.948889,0.000743,0.017927,0.005624,0,0.02954,0.068626,0.180453,0.203518,0.281601,298.256256,372.117493,2816.574219,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150679,156908,157056,152019 -7.10161,-0.025584,-0.008334,-0.950109,0.026285,0.016863,0.007752,0,0.02954,0.068626,0.180453,0.203518,0.281601,300.209229,325.24588,2794.851562,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150745,156935,156985,151996 -7.106611,-0.035105,-0.000766,-0.954748,-0.00245,0.008349,0.013073,0,0.02954,0.068626,0.180453,0.203518,0.281601,315.833099,377.97644,2740.545166,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,150731,156844,156968,152119 -7.111612,-0.039256,-0.008578,-0.953527,0.019899,0.004092,0.008816,0,0.02954,0.068626,0.180453,0.203518,0.281601,323.64505,336.963776,2783.990234,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,151094,157309,157336,152415 -7.116613,-0.039744,-0.000766,-0.961828,-0.003514,-0.003358,0.014137,0,0.02954,0.068626,0.180453,0.203518,0.281601,337.315918,379.929413,2729.683838,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,151092,157226,157311,152526 -7.121614,-0.038035,0.000455,-0.963537,0.000743,-0.011872,0.010945,0,0.02954,0.068626,0.180453,0.203518,0.281601,352.939789,372.117493,2762.267822,0,0,-0.188617,0.163582,0.136208,-0.116584,-0.150913,-0.134892,0.089533,0.334481,0,151051,157282,157320,152501 -7.126616,-0.03242,-0.000277,-0.968176,-0.001385,-0.015064,0.016266,0,0.031957,0.07115,0.187385,0.208202,0.24282,371.519928,384.618591,2312.166504,0,0,-0.187264,0.172737,0.115627,-0.113294,-0.155429,-0.137052,0.089533,0.334481,0,151470,156838,156864,152982 -7.131617,-0.047312,0.010465,-0.964025,-0.009899,-0.022514,0.01733,0,0.03429,0.073114,0.185804,0.206848,0.250766,382.288483,397.757111,2382.395264,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,151376,156905,156936,152936 -7.136618,-0.035594,0.003141,-0.971594,0.002872,-0.031028,0.016266,0,0.03429,0.073114,0.185804,0.206848,0.250766,397.912354,374.321289,2393.256592,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152132,157714,157667,153676 -7.141619,-0.048289,0.012174,-0.972326,-0.016285,-0.025706,0.018394,0,0.03429,0.073114,0.185804,0.206848,0.250766,388.14743,409.475006,2371.533936,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152128,157648,157690,153724 -7.14662,-0.02241,0.013883,-0.984777,0.003936,-0.037413,0.013073,0,0.03429,0.073114,0.185804,0.206848,0.250766,409.630249,372.368317,2425.840332,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152090,157761,157686,153654 -7.151621,-0.047557,0.014859,-0.980383,-0.017349,-0.03422,0.015202,0,0.03429,0.073114,0.185804,0.206848,0.250766,403.771301,411.427979,2404.11792,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152078,157694,157709,153709 -7.156622,-0.033641,0.01608,-0.992102,-0.007771,-0.048055,0.014137,0,0.03429,0.073114,0.185804,0.206848,0.250766,429.160095,393.851135,2414.979004,0,0,-0.187131,0.176019,0.108562,-0.112339,-0.151514,-0.133734,0.089533,0.334481,0,152357,158045,157974,154003 -7.161623,-0.052684,0.014615,-0.985021,-0.021606,-0.036349,0.01733,0,0.034556,0.076417,0.192396,0.217697,0.224836,419.774536,439.148804,2117.760986,0,0,-0.186494,0.179379,0.101209,-0.111117,-0.15784,-0.14128,0.089533,0.334481,0,152618,157693,157732,154336 -7.166624,-0.04951,0.005338,-0.987219,-0.013092,-0.052312,0.01733,0,0.036654,0.077008,0.188155,0.20997,0.247249,441.286743,409.344971,2346.510742,0,0,-0.186568,0.186413,0.086255,-0.108851,-0.151501,-0.132962,0.089533,0.334481,0,152397,157973,157909,154099 -7.171625,-0.045848,0.010953,-0.980627,-0.018413,-0.039541,0.018394,0,0.037087,0.079101,0.192875,0.218182,0.212564,426.512482,434.179932,1981.658447,0,0,-0.185859,0.190014,0.078614,-0.107459,-0.155788,-0.139081,0.089533,0.334481,0,152752,157568,157584,154474 -7.176626,-0.041941,-0.007113,-0.983312,-0.009899,-0.054441,0.020523,0,0.037087,0.079101,0.192875,0.218182,0.212564,453.854248,418.556061,1959.935913,0,0,-0.185859,0.190014,0.078614,-0.107459,-0.155788,-0.139081,0.089533,0.334481,0,152762,157590,157519,154507 -7.181627,-0.024852,0.016812,-0.984289,-0.010963,-0.045927,0.016266,0,0.037447,0.083214,0.194248,0.222838,0.224946,440.749146,429.053314,2129.744873,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152596,157737,157714,154336 -7.186628,-0.03657,-0.003451,-0.986242,0.000743,-0.06189,0.018394,0,0.037447,0.083214,0.194248,0.222838,0.224946,470.043915,407.570496,2108.022217,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152610,157766,157641,154365 -7.191629,-0.042674,0.008756,-0.987951,-0.008835,-0.057633,0.023715,0,0.037447,0.083214,0.194248,0.222838,0.224946,462.231964,425.147369,2053.71582,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152654,157686,157612,154429 -7.19663,-0.061961,-0.011264,-0.983801,0.010321,-0.06189,0.02478,0,0.037447,0.083214,0.194248,0.222838,0.224946,470.043915,389.993652,2042.854614,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152693,157718,157558,154413 -7.201632,-0.053904,0.004605,-0.986975,0.006064,-0.049119,0.030101,0,0.037447,0.083214,0.194248,0.222838,0.224946,446.608093,397.805573,1988.548218,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152744,157614,157516,154432 -7.206633,-0.033641,0.007047,-0.982336,0.027349,-0.056569,0.027972,0,0.037447,0.083214,0.194248,0.222838,0.224946,460.278992,358.745911,2010.270752,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152747,157688,157485,154385 -7.211634,-0.02827,0.01315,-0.987463,0.03267,-0.053376,0.030101,0,0.037447,0.083214,0.194248,0.222838,0.224946,454.420044,348.980988,1988.548218,0,0,-0.185648,0.193652,0.070623,-0.106301,-0.156801,-0.139624,0.089533,0.334481,0,152785,157670,157460,154391 -7.216635,-0.029246,0.03024,-0.982336,0.048633,-0.053376,0.030101,0,0.040285,0.083338,0.195573,0.222346,0.259162,456.853088,318.784637,2337.756592,0,0,-0.186231,0.197503,0.062519,-0.105039,-0.155289,-0.139008,0.089533,0.334481,0,152463,158052,157776,154014 -7.221636,-0.04365,0.018033,-0.988928,0.05289,-0.057633,0.031165,0,0.041178,0.086471,0.19879,0.216311,0.263751,470.567291,299.89798,2373.727539,0,0,-0.187107,0.209463,0.037533,-0.101701,-0.157612,-0.12984,0.089533,0.334481,0,152994,158683,158342,154535 -7.226637,-0.054148,0.028043,-0.983557,0.057147,-0.048055,0.031165,0,0.041178,0.086471,0.19879,0.216311,0.263751,452.990448,292.086029,2373.727539,0,0,-0.187107,0.209463,0.037533,-0.101701,-0.157612,-0.12984,0.089533,0.334481,0,153020,158673,158351,154510 -7.231638,-0.062937,0.018521,-0.977941,0.079496,-0.052312,0.032229,0,0.044573,0.089617,0.204107,0.222253,0.270843,470.560303,261.97757,2435.246826,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,152971,158782,158365,154436 -7.236639,-0.058299,0.025113,-0.988439,0.078432,-0.036349,0.041807,0,0.044573,0.089617,0.204107,0.222253,0.270843,441.265533,263.930542,2337.495361,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153096,158653,158299,154506 -7.24164,-0.033641,0.017545,-0.996008,0.109294,-0.055505,0.040743,0,0.044573,0.089617,0.204107,0.222253,0.270843,476.41925,207.294022,2348.356689,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153106,158756,158218,154474 -7.246641,-0.054393,0.013883,-0.994787,0.114615,-0.036349,0.042872,0,0.044573,0.089617,0.204107,0.222253,0.270843,441.265533,197.529099,2326.634033,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153876,159412,158924,155154 -7.251642,-0.039012,0.025113,-0.999914,0.141221,-0.064019,0.042872,0,0.044573,0.089617,0.204107,0.222253,0.270843,492.043121,148.704498,2326.634033,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153874,159511,158825,155156 -7.256643,-0.061961,0.001187,-0.998693,0.151863,-0.03422,0.045,0,0.044573,0.089617,0.204107,0.222253,0.270843,437.359558,129.174667,2304.911377,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153970,159455,158838,155103 -7.261644,-0.050486,0.010709,-1.015783,0.169955,-0.051248,0.045,0,0.044573,0.089617,0.204107,0.222253,0.270843,468.6073,95.973938,2304.911377,0,0,-0.187451,0.213717,0.028899,-0.100162,-0.159534,-0.132637,0.089533,0.334481,0,153972,159519,158774,155101 -7.266645,-0.075877,0.004117,-1.007971,0.184854,-0.025706,0.046064,0,0.044184,0.089198,0.204167,0.217466,0.228434,421.844971,59.846752,1861.225464,0,0,-0.186249,0.226648,0.002861,-0.096305,-0.159982,-0.128268,0.089533,0.334481,0,155376,159942,159218,156339 -7.271646,-0.058787,0.002164,-1.015295,0.210396,-0.02145,0.047128,0,0.04702,0.091081,0.207762,0.216684,0.197385,420.631866,11.539858,1533.486694,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155753,159661,158843,156617 -7.276648,-0.060984,0.008756,-1.015295,0.221038,-0.000165,0.047128,0,0.04702,0.091081,0.207762,0.216684,0.197385,381.572205,-7.989988,1533.486694,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155811,159642,158862,156559 -7.281649,-0.047801,-0.007113,-1.027014,0.248708,0.008349,0.05245,0,0.04702,0.091081,0.207762,0.216684,0.197385,365.948334,-58.767559,1479.18042,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155932,159622,158773,156547 -7.28665,-0.042186,0.022428,-1.019934,0.245515,0.017927,0.051385,0,0.04702,0.091081,0.207762,0.216684,0.197385,348.37146,-52.908604,1490.041626,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,155933,159610,158807,156524 -7.291651,-0.05952,-0.006137,-1.009436,0.278506,0.039211,0.053514,0,0.04702,0.091081,0.207762,0.216684,0.197385,309.311798,-113.451096,1468.319092,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,156608,160164,159318,157000 -7.296652,-0.046824,0.027799,-1.009924,0.255093,0.029633,0.053514,0,0.04702,0.091081,0.207762,0.216684,0.197385,326.888641,-70.485435,1468.319092,0,0,-0.185325,0.231152,-0.005941,-0.095047,-0.160742,-0.125603,0.089533,0.334481,0,156548,160138,159343,157061 -7.301653,-0.085398,-0.003207,-1.012609,0.290212,0.058367,0.056706,0,0.016103,0.031311,0.173389,0.14631,0.1862,211.079056,-264.078735,1321.584229,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157004,160069,159119,156898 -7.306654,-0.068064,0.025846,-1.021643,0.272121,0.056239,0.058835,0,0.016103,0.031311,0.173389,0.14631,0.1862,214.985031,-230.878036,1299.861694,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,156989,160018,159126,156957 -7.311655,-0.079051,0.011441,-1.014562,0.298726,0.071138,0.058835,0,0.016103,0.031311,0.173389,0.14631,0.1862,187.64325,-279.702637,1299.861694,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157348,160323,159388,157164 -7.316656,-0.05073,0.020963,-1.020178,0.293405,0.082845,0.062028,0,0.016103,0.031311,0.173389,0.14631,0.1862,166.160431,-269.937714,1267.277954,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157392,160259,159387,157184 -7.321657,-0.049266,0.031217,-1.01676,0.298726,0.082845,0.062028,0,0.016103,0.031311,0.173389,0.14631,0.1862,166.160431,-279.702637,1267.277954,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157402,160269,159377,157175 -7.326658,-0.045359,0.017545,-1.037756,0.296598,0.092423,0.066285,0,0.016103,0.031311,0.173389,0.14631,0.1862,148.583572,-275.796661,1223.832764,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157459,160204,159355,157204 -7.331659,-0.043895,0.043668,-1.029699,0.27957,0.086037,0.067349,0,0.016103,0.031311,0.173389,0.14631,0.1862,160.301483,-244.54895,1212.971558,0,0,-0.183405,0.245197,-0.033105,-0.091406,-0.157286,-0.114999,0.089533,0.334481,0,157530,160276,159467,157361 -7.33666,-0.062693,0.012662,-1.026525,0.294469,0.103065,0.071606,0,0.061309,0.119574,0.216748,0.231977,0.182303,208.623077,-114.680603,1129.75647,0,0,-0.183109,0.250003,-0.042463,-0.090178,-0.15544,-0.112404,0.089533,0.334481,0,157435,160112,159465,157623 -7.341661,-0.064402,0.042203,-1.043859,0.247643,0.08923,0.077991,0,0.045345,0.101756,0.211988,0.181532,0.458522,225.275558,-121.323242,3883.623779,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154671,162889,162196,154879 -7.346663,-0.08076,0.007047,-1.047033,0.276378,0.106257,0.073734,0,0.045345,0.101756,0.211988,0.181532,0.458522,194.027817,-174.053802,3927.068848,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154711,162954,162217,154751 -7.351664,-0.075145,0.0361,-1.049963,0.225295,0.108386,0.084376,0,0.045345,0.101756,0.211988,0.181532,0.458522,190.121841,-80.310562,3818.456055,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154730,162747,162207,154950 -7.356665,-0.066355,0.016324,-1.051916,0.258286,0.10945,0.082248,0,0.045345,0.101756,0.211988,0.181532,0.458522,188.168869,-140.853088,3840.178711,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154870,162927,162269,154965 -7.361666,-0.068309,0.012174,-1.069006,0.213588,0.121157,0.090762,0,0.045345,0.101756,0.211988,0.181532,0.458522,166.686035,-58.827763,3753.288574,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154896,162736,162285,155112 -7.366667,-0.044627,0.016812,-1.0734,0.228487,0.104129,0.089697,0,0.045345,0.101756,0.211988,0.181532,0.458522,197.933792,-86.169518,3764.149658,0,0,-0.193279,0.264456,-0.073489,-0.087678,-0.166643,-0.079775,0.089533,0.334481,0,154882,162806,162238,155105 -7.371668,-0.063182,0.000455,-1.080725,0.200818,0.122221,0.10034,0,0.057154,0.100306,0.220658,0.172981,0.286587,180.644913,-51.08297,1900.801758,0,0,-0.190796,0.28022,-0.102801,-0.084849,-0.163504,-0.072676,0.089533,0.334481,0,156727,160890,160427,156986 -7.376669,-0.043406,0.022672,-1.084143,0.192304,0.092423,0.103532,0,0.057154,0.100306,0.220658,0.172981,0.286587,235.328476,-35.459091,1868.218018,0,0,-0.190796,0.28022,-0.102801,-0.084849,-0.163504,-0.072676,0.089533,0.334481,0,156693,160901,160359,157093 -7.38167,-0.072703,-0.005648,-1.085852,0.172083,0.112643,0.112046,0,0.057154,0.100306,0.220658,0.172981,0.286587,198.221771,1.647587,1781.327881,0,0,-0.190796,0.28022,-0.102801,-0.084849,-0.163504,-0.072676,0.089533,0.334481,0,156780,160739,160346,157180 -7.386671,-0.055125,0.023893,-1.1005,0.144414,0.08178,0.117367,0,0.0546,0.10806,0.217509,0.176964,0.318973,249.078918,59.733551,2057.544922,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156395,161008,160630,157013 -7.391672,-0.086375,-0.006381,-1.088781,0.143349,0.120092,0.126945,0,0.0546,0.10806,0.217509,0.176964,0.318973,178.7715,61.686535,1959.793457,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156561,160838,160604,157042 -7.396673,-0.07368,0.016812,-1.110266,0.103973,0.088166,0.136523,0,0.0546,0.10806,0.217509,0.176964,0.318973,237.361023,133.946945,1862.041992,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156528,160727,160520,157271 -7.401674,-0.086375,0.007779,-1.106115,0.105037,0.128606,0.138652,0,0.0546,0.10806,0.217509,0.176964,0.318973,163.147644,131.993973,1840.319458,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156624,160631,160569,157214 -7.406675,-0.078074,0.002164,-1.106115,0.075239,0.104129,0.150358,0,0.0546,0.10806,0.217509,0.176964,0.318973,208.066269,186.677505,1720.845581,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156644,160502,160459,157433 -7.411676,-0.070994,0.017545,-1.099523,0.059276,0.126478,0.150358,0,0.0546,0.10806,0.217509,0.176964,0.318973,167.053619,215.972275,1720.845581,0,0,-0.19093,0.285594,-0.113091,-0.084113,-0.162909,-0.068904,0.089533,0.334481,0,156656,160431,160529,157422 -7.416677,-0.065623,-0.011264,-1.102209,0.045441,0.112643,0.156744,0,0.059719,0.102206,0.222444,0.170981,0.239923,201.498535,230.381775,848.909546,0,0,-0.189346,0.291269,-0.123155,-0.083388,-0.162725,-0.068775,0.089533,0.334481,0,157479,159580,159637,158342 -7.421679,-0.055125,0.026822,-1.105627,0.011385,0.112643,0.157808,0,0.059288,0.107616,0.217677,0.177598,0.187801,192.750763,305.02002,306.099945,0,0,-0.185459,0.308589,-0.15405,-0.08198,-0.15839,-0.069982,0.089533,0.334481,0,157684,158681,158906,158679 -7.42668,-0.061717,-0.007602,-1.104406,0.005,0.103065,0.163129,0,0.059288,0.107616,0.217677,0.177598,0.187801,210.327606,316.737915,251.793549,0,0,-0.185459,0.308589,-0.15405,-0.08198,-0.15839,-0.069982,0.089533,0.334481,0,157709,158633,158846,158763 -7.431681,-0.053172,0.027066,-1.099035,-0.045019,0.093487,0.167386,0,0.066857,0.105287,0.224705,0.17841,0.115969,240.800568,410.018951,-524.75415,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158361,157794,158132,159663 -7.436682,-0.077342,-0.001498,-1.095129,-0.052468,0.099872,0.170579,0,0.066857,0.105287,0.224705,0.17841,0.115969,229.082657,423.689819,-557.338013,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158392,157736,158125,159698 -7.441683,-0.059031,0.029752,-1.101965,-0.105679,0.083909,0.176964,0,0.066857,0.105287,0.224705,0.17841,0.115969,258.377411,521.338989,-622.505493,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158100,157372,157898,159660 -7.446684,-0.088572,0.007535,-1.090002,-0.108872,0.104129,0.176964,0,0.066857,0.105287,0.224705,0.17841,0.115969,221.270737,527.197937,-622.505493,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158132,157329,157941,159628 -7.451685,-0.068553,0.026334,-1.095861,-0.149313,0.095615,0.183349,0,0.066857,0.105287,0.224705,0.17841,0.115969,236.894592,601.411377,-687.673157,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158107,157205,157934,159783 -7.456686,-0.081736,0.022184,-1.086584,-0.155698,0.10945,0.184414,0,0.066857,0.105287,0.224705,0.17841,0.115969,211.505814,613.129211,-698.534485,0,0,-0.183074,0.314896,-0.164316,-0.081636,-0.157847,-0.073123,0.089533,0.334481,0,158131,157157,157961,159781 -7.461687,-0.067332,0.027799,-1.09635,-0.184432,0.115836,0.189735,0,0.063008,0.113245,0.21899,0.192147,0.099716,189.3004,691.067932,-918.709106,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158296,156837,157841,160057 -7.466688,-0.052928,0.033658,-1.084631,-0.20146,0.115836,0.18867,0,0.063008,0.113245,0.21899,0.192147,0.099716,189.3004,722.315674,-907.847839,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158256,156819,157885,160079 -7.471689,-0.057078,0.025113,-1.088537,-0.208909,0.12967,0.192927,0,0.063008,0.113245,0.21899,0.192147,0.099716,163.911621,735.986572,-951.292969,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158311,156736,157880,160111 -7.47669,-0.045359,0.047818,-1.085363,-0.237643,0.117964,0.193992,0,0.063008,0.113245,0.21899,0.192147,0.099716,185.39444,788.717102,-962.154236,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158248,156694,157901,160196 -7.481691,-0.062449,0.024625,-1.086828,-0.231258,0.121157,0.192927,0,0.063008,0.113245,0.21899,0.192147,0.099716,179.535477,776.999207,-951.292969,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158254,156711,157906,160167 -7.486692,-0.052439,0.05441,-1.077062,-0.263185,0.114771,0.189735,0,0.063008,0.113245,0.21899,0.192147,0.099716,191.253387,835.588745,-918.709106,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158225,156770,158059,160279 -7.491693,-0.064402,0.024869,-1.069494,-0.237643,0.115836,0.18867,0,0.063008,0.113245,0.21899,0.192147,0.099716,189.3004,788.717102,-907.847839,0,0,-0.179593,0.333558,-0.19664,-0.081558,-0.155982,-0.078902,0.089533,0.334481,0,158263,156826,158025,160219 -7.496695,-0.072215,0.037809,-1.077307,-0.274891,0.112643,0.192927,0,0.065107,0.116785,0.221244,0.196737,0.127133,199.297287,865.494873,-671.486023,0,0,-0.1794,0.339828,-0.207872,-0.081775,-0.156137,-0.079952,0.089533,0.334481,0,157940,156996,158328,160070 -7.501696,-0.07783,0.015592,-1.073889,-0.242965,0.114771,0.189735,0,0.073504,0.110478,0.223881,0.206801,-0.068366,200.228775,825.37384,-2634.121338,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159942,155074,156325,161993 -7.506697,-0.081492,0.017057,-1.07633,-0.279148,0.119028,0.195056,0,0.073504,0.110478,0.223881,0.206801,-0.068366,192.41684,891.77533,-2688.427734,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159938,154946,156344,162106 -7.511698,-0.080271,0.002896,-1.068029,-0.244029,0.119028,0.18867,0,0.073504,0.110478,0.223881,0.206801,-0.068366,192.41684,827.326843,-2623.26001,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159935,155073,156343,161975 -7.516699,-0.083201,0.00192,-1.074865,-0.266378,0.128606,0.192927,0,0.073504,0.110478,0.223881,0.206801,-0.068366,174.839981,868.339539,-2666.705322,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159955,154971,156358,162041 -7.5217,-0.068309,0.000699,-1.066564,-0.242965,0.121157,0.186542,0,0.073504,0.110478,0.223881,0.206801,-0.068366,188.510864,825.37384,-2601.537598,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159919,155093,156367,161947 -7.526701,-0.074656,-0.004184,-1.059729,-0.245093,0.139248,0.186542,0,0.073504,0.110478,0.223881,0.206801,-0.068366,155.310135,829.279846,-2601.537598,0,0,-0.171718,0.36061,-0.240455,-0.082313,-0.150377,-0.096322,0.089533,0.334481,0,159948,155056,156404,161918 -7.531702,-0.057078,0.007779,-1.060949,-0.237643,0.1169,0.182285,0,0.068505,0.122699,0.216012,0.224166,-0.043547,181.882645,847.476746,-2304.795654,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159754,155508,156839,161813 -7.536703,-0.067332,0.00192,-1.05924,-0.225937,0.136056,0.182285,0,0.068505,0.122699,0.216012,0.224166,-0.043547,146.728943,825.993896,-2304.795654,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159811,155494,156853,161756 -7.541704,-0.052439,0.016324,-1.066564,-0.233387,0.104129,0.181221,0,0.068505,0.122699,0.216012,0.224166,-0.043547,205.318466,839.664795,-2293.934326,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159727,155550,156819,161817 -7.546705,-0.064891,0.012906,-1.051672,-0.215295,0.125414,0.178028,0,0.068505,0.122699,0.216012,0.224166,-0.043547,166.258789,806.46405,-2261.350586,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159767,155577,156857,161713 -7.551706,-0.056834,0.029508,-1.05802,-0.22913,0.096679,0.1759,0,0.068505,0.122699,0.216012,0.224166,-0.043547,218.989334,831.852844,-2239.628174,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159955,155914,157140,162057 -7.556707,-0.068309,0.026822,-1.051672,-0.204652,0.115836,0.174836,0,0.068505,0.122699,0.216012,0.224166,-0.043547,183.835632,786.934204,-2228.766846,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,160024,155935,157141,161966 -7.561708,-0.065379,0.036832,-1.063146,-0.219552,0.092423,0.172707,0,0.068505,0.122699,0.216012,0.224166,-0.043547,226.801285,814.276001,-2207.044189,0,0,-0.169591,0.380944,-0.275174,-0.083846,-0.147507,-0.101468,0.089533,0.334481,0,159932,155972,157147,162015 -7.56671,-0.067576,0.039029,-1.056066,-0.185496,0.115836,0.166322,0,0.077247,0.117799,0.224824,0.223397,-0.107857,200.006302,750.36908,-2798.217773,0,0,-0.167757,0.388222,-0.286705,-0.084367,-0.147577,-0.105598,0.089533,0.334481,0,160614,155418,156519,162515 -7.571711,-0.065379,0.034391,-1.067297,-0.197203,0.095615,0.164193,0,0.074233,0.124761,0.217603,0.235151,-0.138711,223.861664,793.422363,-3091.38208,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160841,155106,156245,162875 -7.576712,-0.067576,0.041959,-1.063391,-0.161019,0.10945,0.154615,0,0.074233,0.124761,0.217603,0.235151,-0.138711,198.47287,727.020874,-2993.630615,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160740,155149,156206,162591 -7.581713,-0.070262,0.028531,-1.065344,-0.169533,0.098808,0.156744,0,0.074233,0.124761,0.217603,0.235151,-0.138711,218.002701,742.644775,-3015.353271,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160726,155132,156181,162648 -7.586714,-0.060252,0.033658,-1.057775,-0.131221,0.107322,0.146101,0,0.074233,0.124761,0.217603,0.235151,-0.138711,202.378845,672.337341,-2906.740479,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160704,155295,156235,162453 -7.591715,-0.068797,0.024869,-1.058508,-0.137606,0.105193,0.146101,0,0.074233,0.124761,0.217603,0.235151,-0.138711,206.284805,684.055298,-2906.740479,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160688,155287,156243,162469 -7.596716,-0.056102,0.02902,-1.054357,-0.104615,0.100936,0.136523,0,0.074233,0.124761,0.217603,0.235151,-0.138711,214.096741,623.512756,-2808.989014,0,0,-0.16438,0.410067,-0.322405,-0.086499,-0.14337,-0.11039,0.089533,0.334481,0,160126,154936,155755,161801 -7.601717,-0.071727,0.018766,-1.045568,-0.107808,0.110514,0.136523,0,0.074673,0.128206,0.217683,0.23993,-0.124607,196.666977,638.142029,-2665.043457,0,0,-0.163702,0.424531,-0.347049,-0.088231,-0.14301,-0.111725,0.089533,0.334481,0,159985,155048,155931,161654 -7.606718,-0.058055,0.025113,-1.050451,-0.085459,0.096679,0.129074,0,0.089477,0.117668,0.228576,0.232425,-0.267071,242.046722,583.356873,-4042.97876,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,161372,153770,154453,163023 -7.611719,-0.065379,0.013639,-1.039221,-0.082267,0.1169,0.125881,0,0.089477,0.117668,0.228576,0.232425,-0.267071,204.940033,577.497925,-4010.394775,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,161382,153772,154517,162947 -7.61672,-0.044139,0.023648,-1.04215,-0.069496,0.094551,0.115239,0,0.089477,0.117668,0.228576,0.232425,-0.267071,245.952682,554.062134,-3901.781982,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,161256,153945,154561,162856 -7.621721,-0.053416,0.013639,-1.030187,-0.058854,0.111579,0.11311,0,0.089477,0.117668,0.228576,0.232425,-0.267071,214.704956,534.532288,-3880.05957,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,157849,150519,151158,159348 -7.626722,-0.038523,0.025357,-1.039221,-0.055661,0.08178,0.109918,0,0.089477,0.117668,0.228576,0.232425,-0.267071,269.388489,528.67334,-3847.47583,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,157768,150612,151130,159364 -7.631723,-0.057078,0.017789,-1.025549,-0.037569,0.092423,0.105661,0,0.089477,0.117668,0.228576,0.232425,-0.267071,249.858658,495.472626,-3804.030518,0,0,-0.16046,0.432841,-0.358695,-0.089025,-0.139099,-0.114757,0.089533,0.334481,0,157777,150669,151160,159268 -7.636724,-0.048289,0.024869,-1.036047,-0.043954,0.06901,0.102468,0,0.067557,0.14036,0.205886,0.251562,-0.11955,251.184753,542.308655,-2265.871826,0,0,-0.162191,0.454155,-0.397713,-0.092197,-0.138329,-0.111202,0.089533,0.334481,0,156191,152162,152744,157778 -7.641726,-0.06367,0.019742,-1.020422,-0.018413,0.075395,0.096083,0,0.084861,0.129237,0.222493,0.238979,-0.173892,269.942993,472.345856,-2755.311035,0,0,-0.161425,0.461941,-0.410496,-0.093343,-0.137633,-0.109742,0.089533,0.334481,0,149223,144252,144657,150707 -7.646727,-0.059275,0.023893,-1.034338,-0.025863,0.06156,0.093954,0,0.084861,0.129237,0.222493,0.238979,-0.173892,295.331757,486.016724,-2733.588379,0,0,-0.161425,0.461941,-0.410496,-0.093343,-0.137633,-0.109742,0.089533,0.334481,0,149162,144285,144667,150724 -7.651728,-0.061473,0.024625,-1.015783,0.009257,0.063688,0.087569,0,0.083746,0.133366,0.217717,0.247795,-0.222316,282.661072,437.747009,-3162.621582,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,149652,143892,144202,151093 -7.656729,-0.05952,0.017545,-1.01798,-0.001385,0.059432,0.087569,0,0.083746,0.133366,0.217717,0.247795,-0.222316,290.473022,457.276825,-3162.621582,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,149624,143880,144214,151120 -7.66173,-0.055369,0.02316,-1.004553,0.036927,0.046661,0.080119,0,0.083746,0.133366,0.217717,0.247795,-0.222316,313.908813,386.969421,-3086.592529,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135792,130247,130393,137194 -7.666731,-0.069041,0.014371,-1.004064,0.030541,0.05411,0.082248,0,0.083746,0.133366,0.217717,0.247795,-0.222316,300.237946,398.687317,-3108.315186,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135816,130200,130397,137214 -7.671732,-0.058787,0.020963,-0.985266,0.063532,0.034954,0.077991,0,0.083746,0.133366,0.217717,0.247795,-0.222316,335.391632,338.144806,-3064.869873,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135798,130339,130344,137145 -7.676733,-0.060008,0.009,-0.978918,0.063532,0.04134,0.075863,0,0.083746,0.133366,0.217717,0.247795,-0.222316,323.673737,338.144806,-3043.147461,0,0,-0.159889,0.470092,-0.423288,-0.094141,-0.133971,-0.114429,0.089533,0.334481,0,135788,130349,130378,137111 -7.681734,-0.035105,0.023648,-0.960607,0.092266,0.023248,0.067349,0,0.074348,0.141323,0.205736,0.25058,-0.152841,334.887909,290.524475,-2247.20874,0,0,-0.16056,0.484971,-0.450223,-0.096557,-0.131388,-0.109257,0.089533,0.334481,0,135028,131204,131115,136279 -7.686735,-0.048289,0.022184,-0.944006,0.096523,0.015798,0.063092,0,0.086953,0.135274,0.215419,0.240675,-0.197439,366.328094,264.535248,-2658.928711,0,0,-0.159839,0.493077,-0.463455,-0.097463,-0.128466,-0.105401,0.089533,0.334481,0,116905,112319,112116,118166 -7.691736,-0.027293,0.029264,-0.929846,0.116744,-0.002294,0.057771,0,0.081129,0.14002,0.207606,0.244914,-0.198416,385.191986,235.207672,-2614.594238,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,116871,112412,112112,118111 -7.696737,-0.058055,0.013395,-0.905187,0.123129,-0.018257,0.055642,0,0.081129,0.14002,0.207606,0.244914,-0.198416,414.486725,223.489792,-2592.871582,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,116831,112475,112093,118107 -7.701738,-0.046336,0.023648,-0.902014,0.122065,-0.019321,0.05245,0,0.081129,0.14002,0.207606,0.244914,-0.198416,416.439728,225.442764,-2560.287842,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,116795,112507,112125,118079 -7.706739,-0.062205,0.016568,-0.866125,0.138028,-0.038477,0.050321,0,0.081129,0.14002,0.207606,0.244914,-0.198416,451.593414,196.147995,-2538.565186,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109472,105298,104787,110768 -7.71174,-0.06074,0.027311,-0.844641,0.131643,-0.026771,0.051385,0,0.081129,0.14002,0.207606,0.244914,-0.198416,430.110596,207.865906,-2549.426514,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109493,105254,104810,110769 -7.716742,-0.045115,0.022916,-0.829992,0.16357,-0.060826,0.046064,0,0.081129,0.14002,0.207606,0.244914,-0.198416,492.606079,149.276398,-2495.120117,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109435,105430,104743,110719 -7.721743,-0.035594,0.025602,-0.804846,0.16357,-0.050184,0.043936,0,0.081129,0.14002,0.207606,0.244914,-0.198416,473.076263,149.276398,-2473.397705,0,0,-0.159338,0.501085,-0.47687,-0.098489,-0.126478,-0.104894,0.089533,0.334481,0,109433,105432,104784,110677 -7.726744,-0.005564,0.0361,-0.800451,0.161441,-0.086367,0.03755,0,0.084299,0.1416,0.219547,0.242464,-0.207822,561.391052,148.686157,-2504.219971,0,0,-0.158378,0.525331,-0.517803,-0.101139,-0.135249,-0.100864,0.089533,0.334481,0,109376,105490,104665,110796 -7.731745,-0.04951,0.023404,-0.762609,0.166762,-0.104459,0.03755,0,0.054831,0.162636,0.187579,0.255708,-0.015594,535.926147,163.226196,-542.38208,0,0,-0.162234,0.531364,-0.533002,-0.101202,-0.132748,-0.093072,0.089533,0.334481,0,107433,107420,106674,108831 -7.736746,-0.059275,0.021695,-0.736975,0.167827,-0.108716,0.040743,0,0.054831,0.162636,0.187579,0.255708,-0.015594,543.738037,161.273209,-574.965881,0,0,-0.162234,0.531364,-0.533002,-0.101202,-0.132748,-0.093072,0.089533,0.334481,0,107459,107397,106632,108869 -7.741747,-0.054148,0.008512,-0.723059,0.190175,-0.131065,0.038615,0,0.117246,0.121577,0.247779,0.213784,-0.295053,695.225342,43.324322,-3405.343994,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110256,104836,103532,111733 -7.746748,-0.020213,0.034635,-0.686926,0.186983,-0.127872,0.035422,0,0.117246,0.121577,0.247779,0.213784,-0.295053,689.366394,49.183273,-3372.760254,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110224,104857,103577,111701 -7.751749,-0.007518,0.032682,-0.687902,0.18379,-0.167248,0.031165,0,0.117246,0.121577,0.247779,0.213784,-0.295053,761.62677,55.042202,-3329.315186,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110164,105029,103616,111797 -7.75675,-0.05073,0.020475,-0.654943,0.196561,-0.17257,0.035422,0,0.117246,0.121577,0.247779,0.213784,-0.295053,771.391724,31.606413,-3372.760254,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110221,105019,103539,111827 -7.761751,-0.04658,0.025846,-0.625646,0.200818,-0.169377,0.032229,0,0.117246,0.121577,0.247779,0.213784,-0.295053,765.532776,23.794476,-3340.17627,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110202,105053,103570,111781 -7.766752,-0.020701,0.018521,-0.640051,0.205074,-0.201304,0.031165,0,0.117246,0.121577,0.247779,0.213784,-0.295053,824.122253,15.982536,-3329.315186,0,0,-0.158889,0.541142,-0.545776,-0.101348,-0.130534,-0.092207,0.089533,0.334481,0,110141,105130,103514,111821 -7.771753,-0.031932,0.041959,-0.611486,0.197625,-0.203432,0.033294,0,0.070572,0.156536,0.21139,0.243836,-0.166261,761.249573,84.803123,-2036.616577,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108849,106298,104945,110541 -7.776754,-0.037791,0.021451,-0.588049,0.212524,-0.218331,0.033294,0,0.070572,0.156536,0.21139,0.243836,-0.166261,788.59137,57.461342,-2036.616577,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108849,106353,104891,110541 -7.781755,-0.022898,0.028775,-0.581457,0.214652,-0.23323,0.031165,0,0.070572,0.156536,0.21139,0.243836,-0.166261,815.933105,53.555374,-2014.893921,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108804,106406,104881,110543 -7.786757,-0.030711,0.040982,-0.560705,0.210396,-0.242809,0.033294,0,0.070572,0.156536,0.21139,0.243836,-0.166261,833.51001,61.367313,-2036.616577,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108800,106394,104850,110590 -7.791758,-0.035838,0.021695,-0.549475,0.21146,-0.266221,0.034358,0,0.070572,0.156536,0.21139,0.243836,-0.166261,876.475647,59.41433,-2047.477783,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108770,106428,104794,110642 -7.796759,-0.033885,0.037076,-0.538,0.213588,-0.270478,0.031165,0,0.070572,0.156536,0.21139,0.243836,-0.166261,884.287537,55.508358,-2014.893921,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108670,106408,104751,110549 -7.80176,-0.033885,0.048551,-0.514074,0.21146,-0.284313,0.03755,0,0.070572,0.156536,0.21139,0.243836,-0.166261,909.676331,59.41433,-2080.061523,0,0,-0.159782,0.565182,-0.588468,-0.09916,-0.140818,-0.0873,0.089533,0.334481,0,108705,106365,104664,110644 -7.806761,-0.036326,0.032437,-0.502844,0.209331,-0.303469,0.039679,0,0.08693,0.141877,0.22657,0.2211,-0.15903,972.686096,21.596989,-2027.983032,0,0,-0.160134,0.573169,-0.602537,-0.097799,-0.13964,-0.079223,0.089533,0.334481,0,108628,106518,104615,110617 -7.811762,-0.026561,0.041715,-0.497229,0.205074,-0.319433,0.035422,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1043.664551,34.786846,-2976.292236,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109492,105627,103609,111649 -7.816763,-0.041697,0.040006,-0.476965,0.207203,-0.326882,0.045,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1057.335449,30.880877,-3074.043701,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109583,105550,103497,111760 -7.821764,-0.03657,0.031461,-0.469885,0.205074,-0.340717,0.046064,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1082.724243,34.786846,-3084.905029,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109565,105561,103465,111800 -7.826765,-0.023387,0.03732,-0.465734,0.196561,-0.360938,0.045,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1119.830933,50.410721,-3074.043701,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109501,105593,103454,111842 -7.831766,-0.037059,0.041471,-0.441564,0.199753,-0.354552,0.053514,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1108.113037,44.551769,-3160.934082,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109606,105500,103373,111911 -7.836767,-0.034129,0.031217,-0.443273,0.190175,-0.379029,0.056706,0,0.095618,0.142563,0.249284,0.224031,-0.256206,1153.031616,62.128628,-3193.517822,0,0,-0.156853,0.600265,-0.643734,-0.090156,-0.153666,-0.081468,0.089533,0.334481,0,109576,105495,103313,112006 -7.841768,-0.029734,0.032682,-0.432287,0.193368,-0.388607,0.056706,0,0.069722,0.158852,0.230424,0.223678,-0.12595,1135.998291,55.623474,-1864.159912,0,0,-0.159895,0.615028,-0.673571,-0.082945,-0.160702,-0.064827,0.089533,0.334481,0,108263,106807,104646,110646 -7.846769,-0.067088,0.069547,-0.429846,0.182726,-0.3918,0.06522,0,0.105465,0.136638,0.266858,0.197858,-0.230062,1208.717407,27.770313,-3013.595947,0,0,-0.158705,0.624321,-0.687302,-0.078415,-0.161393,-0.06122,0.089533,0.334481,0,109368,105758,103396,111841 -7.85177,-0.192088,0.188688,-0.683752,0.32746,-0.253451,0.071606,0,0.089104,0.146444,0.253375,0.202955,-0.229283,930.086731,-228.483124,-3070.804443,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,109960,105678,103361,111363 -7.856771,-0.230418,0.187955,-0.908117,0.521149,-0.027835,0.071606,0,0.089104,0.146444,0.253375,0.202955,-0.229283,516.054199,-583.926147,-3070.804443,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,110729,105620,103420,110593 -7.861773,-0.290232,0.266568,-0.944738,0.797848,0.265891,0.054578,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-22.969353,-1091.702026,-2897.02417,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,111599,105759,103622,109370 -7.866774,-0.292186,0.319547,-0.788732,1.093703,0.563874,0.053514,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-569.804749,-1634.63147,-2886.162842,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,112678,105766,103637,108269 -7.871775,-0.282176,0.24899,-0.67008,1.41297,0.816096,0.062028,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-1032.661865,-2220.526367,-2973.052979,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,113814,105802,103427,107307 -7.876776,-0.236766,0.211881,-0.748449,1.657742,1.060868,0.066285,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-1481.848267,-2669.712891,-3016.498291,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,114756,105759,103383,106452 -7.881777,-0.200145,0.173795,-0.77799,1.85356,1.283291,0.048193,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-1890.021729,-3029.061768,-2831.856445,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,115347,105904,103626,105509 -7.886778,-0.168895,0.167691,-0.655187,1.989781,1.455696,0.041807,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-2206.405029,-3279.043945,-2766.688965,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,115849,105902,103757,104878 -7.891779,-0.156199,0.166471,-0.507971,2.136644,1.604687,0.040743,0,0.089104,0.146444,0.253375,0.202955,-0.229283,-2479.822754,-3548.55542,-2755.827637,0,0,-0.157929,0.633352,-0.701164,-0.073233,-0.16427,-0.056511,0.089533,0.334481,0,116381,105909,103772,104324 -7.89678,-0.23823,0.130582,-0.589758,2.256902,1.71111,0.066285,0,0.094157,0.116067,0.20317,0.108756,-0.374636,-2767.252441,-3942.109375,-4499.951172,0,0,-0.150739,0.66922,-0.748811,-0.052563,-0.109014,0.007311,0.089533,0.334481,0,118806,104271,101922,105387 -7.901781,-0.343699,0.248014,-0.980139,1.980203,2.011221,0.18867,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-3414.317139,-3479.802979,-5140.865234,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,119631,102521,102390,105843 -7.906782,-0.435008,0.306363,-1.155676,1.793963,2.502893,0.346176,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-4316.595215,-3138.030762,-6748.333496,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121791,100000,102019,106882 -7.911783,-0.620799,0.340055,-1.686193,0.721224,2.054855,0.520709,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-3494.389404,-1169.42334,-8529.583008,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,120782,100000,101384,111454 -7.916784,-0.353221,0.550748,-1.860021,0.215717,2.282599,0.682471,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-3912.328125,-241.756042,-10180.49609,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121923,100000,101079,113615 -7.921785,-0.669627,0.512906,-1.980627,-0.030119,1.416319,0.886802,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-2322.599121,209.383224,-12265.86035,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121968,100000,100000,117741 -7.926786,-0.508006,0.554166,-2.263586,-0.135478,0.882078,0.983647,0,0.065055,0.123971,0.150682,0.083978,-0.315049,-1342.201294,402.728607,-13254.23633,0,0,-0.150802,0.676211,-0.760505,-0.047318,-0.085627,0.039992,0.089533,0.334481,0,121850,100000,100000,119971 -7.931787,-0.442576,0.437467,-2.230627,0.051826,1.024684,0.913408,0,0.147959,0.074754,0.137049,0.048981,-0.942309,-1628.919312,-5.221539,-18939.07227,0,0,-0.126976,0.712879,-0.785518,-0.032264,0.01091,0.025773,0.089533,0.334481,0,128230,100000,100000,124961 -7.936789,-0.423045,0.546354,-1.897131,0.10823,0.432975,0.884674,0,0.147959,0.074754,0.137049,0.048981,-0.942309,-543.060303,-108.729675,-18645.81836,0,0,-0.126976,0.712879,-0.785518,-0.032264,0.01091,0.025773,0.089533,0.334481,0,126954,100000,100000,125651 -7.94179,-0.493602,0.613248,-1.618811,0.321075,0.404241,0.908087,0,0.147959,0.074754,0.137049,0.048981,-0.942309,-490.329742,-499.326416,-18884.76563,0,0,-0.126976,0.712879,-0.785518,-0.032264,0.01091,0.025773,0.089533,0.334481,0,127531,100000,100000,125552 -7.946791,-0.524607,0.532438,-1.6005,0.255093,0.331873,0.991097,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,12.120502,-549.678711,-28058.23047,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136252,100000,100000,135177 -7.951792,-0.363719,0.34274,-1.571203,0.400892,0.249928,1.012381,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,162.500259,-817.237488,-28275.45508,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136524,100000,100000,135214 -7.956793,-0.309764,0.334928,-1.444738,0.407277,0.322295,0.988968,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,29.69739,-828.955444,-28036.50781,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136429,100000,100000,134831 -7.961794,-0.355906,0.356656,-1.242346,0.265735,0.427654,1.024088,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,-163.648056,-569.208557,-28394.92969,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,136721,100000,100000,135256 -7.966795,-0.326854,0.356656,-1.019445,0.308304,0.401048,1.10284,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,-114.82341,-647.327942,-29198.66406,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,137554,100000,100000,136030 -7.971796,-0.24409,0.263639,-0.946203,0.202946,0.351029,1.166694,0,0.31169,-0.034321,0.338478,-0.04444,-1.758147,-23.03322,-453.982513,-29850.33984,0,0,-0.104412,0.739062,-0.784705,-0.03197,-0.026788,0.010118,0.089533,0.334481,0,137919,100000,100000,136965 -7.976797,-0.159617,0.141813,-0.937902,0.20401,0.468094,1.177336,0,0.204729,-0.035348,0.17397,0.017706,-2.66099,-539.754211,-341.890289,-39173.19141,0,0,-0.042927,0.807064,-0.773606,-0.030316,0.030759,-0.053054,0.089533,0.334481,0,138473,100000,100000,136710 -7.981798,-0.167918,0.186246,-0.868322,0.127386,0.463837,1.179464,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,-558.728638,-213.581131,-41034.28906,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,138364,100000,100000,136819 -7.986799,-0.211863,0.24777,-0.714025,0.096523,0.515984,1.198621,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,-654.424866,-156.944611,-41229.79297,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,138403,100000,100000,136780 -7.9918,-0.162303,0.245572,-0.767004,-0.07056,0.313781,1.225226,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,-283.357941,149.673843,-41501.32422,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137794,100000,100000,137527 -7.996801,-0.151316,0.258756,-0.889807,-0.102487,0.133927,1.199685,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,46.696327,208.263367,-41240.65234,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137406,100000,100000,137915 -8.001802,-0.200877,0.301969,-0.958654,-0.097166,-0.057633,1.144345,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,398.233398,198.498444,-40675.86719,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137064,100000,100000,138257 -8.006804,-0.32783,0.389127,-1.151037,0.031606,-0.081046,1.098583,0,0.203295,-0.047442,0.159373,0.011001,-2.841219,441.199066,-37.812588,-40208.83203,0,0,-0.025447,0.82686,-0.769008,-0.030189,0.043922,-0.058442,0.089533,0.334481,0,137257,100000,100000,138064 -8.011805,-0.361521,0.436734,-1.42301,-0.005642,0.102001,1.10284,0,0.097906,0.055357,0.019547,0.136141,-2.87144,-151.311539,260.18869,-40560.71094,0,0,-0.003315,0.863276,-0.776552,-0.02517,0.078358,-0.080783,0.089533,0.334481,0,137552,100000,100000,137769 -8.016806,-0.368357,0.514371,-1.429846,-0.020541,0.103065,1.099648,0,0.097906,0.055357,0.019547,0.136141,-2.87144,-153.264511,287.530457,-40528.12891,0,0,-0.003315,0.863276,-0.776552,-0.02517,0.078358,-0.080783,0.089533,0.334481,0,137531,100000,100000,137800 -8.021807,-0.375926,0.469449,-1.353674,-0.060982,0.008349,1.087941,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,136.696716,212.115463,-42505.72266,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137317,100000,100000,138014 -8.026808,-0.307078,0.409146,-1.233557,-0.049276,-0.003358,1.060271,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,158.179535,190.632629,-42223.33203,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137317,100000,100000,138014 -8.031809,-0.272898,0.376432,-1.091223,-0.005642,-0.073597,1.028345,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,287.076477,110.560303,-41897.49219,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137268,100000,100000,138063 -8.03681,-0.227,0.329557,-0.956701,-0.030119,-0.06934,1.004931,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,279.264526,155.478928,-41658.54688,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137155,100000,100000,138024 -8.041811,-0.220164,0.286832,-0.858557,0.016706,-0.090624,0.990032,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,318.324188,69.547646,-41506.48828,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137202,100000,100000,137977 -8.046812,-0.211863,0.266813,-0.819982,0.019899,-0.068276,0.988968,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,277.311554,63.688694,-41495.625,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137248,100000,100000,137931 -8.051813,-0.204539,0.250455,-0.812414,0.017771,-0.014,0.991097,0,0.157624,-0.022398,0.082838,0.054605,-3.076919,177.709366,67.594658,-41517.34766,0,0,0.005953,0.877005,-0.776102,-0.024137,0.074787,-0.077002,0.089533,0.334481,0,137344,100000,100000,137835 -8.056814,-0.202586,0.27316,-0.806799,0.026285,0.074331,0.995353,0,0.075028,0.040852,0.096522,0.026617,-3.171982,40.722889,0.610975,-42530.99219,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137548,100000,100000,137631 -8.061815,-0.218699,0.325406,-0.846105,0.051826,0.170111,0.985775,0,0.075028,0.040852,0.096522,0.026617,-3.171982,-135.045654,-46.260635,-42433.23828,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137778,100000,100000,137415 -8.066816,-0.244822,0.37985,-1.060949,0.029477,0.029633,0.947463,0,0.075028,0.040852,0.096522,0.026617,-3.171982,122.748207,-5.247975,-42042.23438,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137479,100000,100000,137714 -8.071817,-0.288523,0.423795,-1.202551,0.06034,-0.033156,0.910215,0,0.075028,0.040852,0.096522,0.026617,-3.171982,237.974243,-61.884502,-41662.08984,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137420,100000,100000,137773 -8.076818,-0.336131,0.468717,-1.230383,0.02522,-0.00655,0.882546,0,0.075028,0.040852,0.096522,0.026617,-3.171982,189.149658,2.56396,-41379.69531,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137405,100000,100000,137788 -8.08182,-0.304393,0.451139,-1.218664,0.02522,0.043468,0.866582,0,0.075028,0.040852,0.096522,0.026617,-3.171982,97.359421,2.56396,-41216.77734,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137502,100000,100000,137701 -8.086821,-0.293162,0.437711,-1.113928,0.045441,0.06156,0.858068,0,0.075028,0.040852,0.096522,0.026617,-3.171982,64.158691,-34.542732,-41129.88672,0,0,0.0207,0.904897,-0.782436,-0.030646,-0.021494,0.014234,0.089533,0.334481,0,137572,100000,100000,137631 -8.091822,-0.266307,0.379605,-0.977941,0.035863,0.071138,0.837848,0,0.504875,-0.32476,0.427208,-0.259985,-4.725514,653.432068,-542.916016,-56778.56641,0,0,0.05686,0.943105,-0.759773,-0.02475,0.077667,-0.064775,0.089533,0.334481,0,137491,100000,100000,137712 -8.096823,-0.213084,0.320035,-0.891516,0.097588,0.055175,0.810178,0,0.053843,-0.032019,0.009677,0.022951,-4.558378,-83.494263,-136.967773,-54790.41016,0,0,0.087721,0.976527,-0.737882,-0.025765,0.044166,-0.054969,0.089533,0.334481,0,137822,100000,100000,137381 -8.101824,-0.199168,0.329313,-0.840002,0.096523,0.018991,0.782508,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,123.047142,-199.706177,-53887.27734,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137672,100000,100000,137519 -8.106825,-0.186473,0.298795,-0.806066,0.078432,0.007285,0.764417,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,144.529968,-166.505447,-53702.63672,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137617,100000,100000,137574 -8.111826,-0.197703,0.325162,-0.829504,-0.008835,-0.022514,0.762288,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,199.213501,-6.36078,-53680.91016,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137403,100000,100000,137788 -8.116827,-0.228221,0.353238,-0.911291,-0.034376,0.011541,0.754838,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,136.718033,40.510834,-53604.88281,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137418,100000,100000,137773 -8.121828,-0.260936,0.423307,-1.037512,-0.006706,-0.018257,0.723976,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,191.401566,-10.266747,-53289.90625,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137414,100000,100000,137777 -8.126829,-0.267527,0.428434,-1.110021,0.056083,-0.010807,0.682471,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,177.730682,-125.49279,-52866.31641,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137540,100000,100000,137645 -8.13183,-0.277293,0.448941,-1.136877,0.051826,-0.029963,0.645223,0,0.133447,-0.0634,0.086042,-0.012301,-4.497556,212.884399,-117.680855,-52486.17188,0,0,0.096722,0.987346,-0.732226,-0.026463,0.047404,-0.051099,0.089533,0.334481,0,137497,100000,100000,137688 -8.136831,-0.252146,0.459439,-1.102209,0.011385,0.004092,0.617553,0,-0.023052,0.123418,-0.103932,0.186339,-4.036829,-198.237488,321.060669,-47501.69141,0,0,0.091095,0.99048,-0.746279,-0.024262,0.08088,-0.06292,0.089533,0.334481,0,137470,100000,100000,137715 -8.141832,-0.24116,0.414762,-1.048742,-0.027991,0.005156,0.598397,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,117.511627,-66.476601,-53532.56641,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137541,100000,100000,137644 -8.146833,-0.238475,0.418668,-0.992102,-0.018413,-0.036349,0.556893,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,193.677994,-84.053452,-53108.97656,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137476,100000,100000,137695 -8.151834,-0.205027,0.369352,-0.916662,0.043312,-0.025706,0.515388,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,174.148148,-197.326508,-52685.38672,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137609,100000,100000,137562 -8.156836,-0.204295,0.35275,-0.869543,0.047569,-0.046991,0.482397,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,213.207825,-205.138443,-52348.6875,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137577,100000,100000,137594 -8.161837,-0.209666,0.354215,-0.881262,0.03267,0.009413,0.463241,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,109.699692,-177.796677,-52153.1875,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137654,100000,100000,137517 -8.166838,-0.198436,0.357145,-0.897375,-0.00245,0.021119,0.45047,0,0.145381,-0.121891,0.069191,-0.064216,-4.646911,88.216866,-113.348213,-52022.85156,0,0,0.107653,1.009864,-0.734536,-0.023854,0.076191,-0.057676,0.089533,0.334481,0,137611,100000,100000,137560 -8.171839,-0.215525,0.365689,-0.943518,-0.00245,0.00622,0.424929,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-154.451828,221.704422,-50483.07813,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137592,100000,100000,137727 -8.17684,-0.213572,0.392301,-1.020178,0.006064,-0.010807,0.391938,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-123.204086,206.080551,-50146.37891,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137577,100000,100000,137742 -8.181841,-0.233348,0.416715,-1.065832,0.024156,-0.000165,0.363203,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-142.733917,172.879837,-49853.125,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137629,100000,100000,137690 -8.186842,-0.242381,0.427701,-1.069738,0.000743,-0.001229,0.337662,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-140.780945,215.845474,-49592.45313,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137584,100000,100000,137735 -8.191843,-0.234812,0.421109,-1.053137,-0.005642,-0.005486,0.311056,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-132.969009,227.563385,-49320.92188,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137497,100000,100000,137686 -8.196844,-0.234324,0.422574,-1.001623,-0.000321,-0.011872,0.278065,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-121.251099,217.798462,-48984.22266,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137495,100000,100000,137688 -8.201845,-0.221629,0.403775,-0.959387,0.008193,-0.019321,0.249331,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-107.580215,202.174591,-48690.96875,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137497,100000,100000,137686 -8.206846,-0.20698,0.387662,-0.933752,0.01245,-0.016128,0.225918,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-113.439163,194.362656,-48452.01953,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137511,100000,100000,137672 -8.211847,-0.211375,0.385465,-0.928137,0.005,-0.002294,0.207827,0,0.00445,0.05417,-0.077944,0.118362,-4.52158,-138.827957,208.033539,-48267.37891,0,0,0.112814,1.021429,-0.736086,-0.023649,0.082395,-0.064192,0.089533,0.334481,0,137524,100000,100000,137663 -8.216848,-0.219187,0.386686,-0.946691,-0.001385,-0.00655,0.193992,0,0.058494,-0.04663,-0.020143,0.013487,-4.774475,-24.944469,27.292582,-50707.17578,0,0,0.125816,1.037905,-0.727206,-0.023742,0.078637,-0.060117,0.089533,0.334481,0,137591,100000,100000,137596 -8.221849,-0.223338,0.400113,-0.982092,0.001807,-0.010807,0.178028,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-99.135567,108.01194,-50392.55469,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137585,100000,100000,137602 -8.226851,-0.227488,0.402799,-1.013586,0.006064,-0.00655,0.158872,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-106.947502,100.200005,-50197.05078,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137600,100000,100000,137587 -8.231852,-0.223582,0.405484,-1.025061,-0.003514,-0.009743,0.139716,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-101.088554,117.776855,-50001.55078,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137577,100000,100000,137610 -8.236853,-0.216502,0.390836,-1.004553,0.000743,-0.008679,0.118432,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-103.041534,109.96492,-49784.32422,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137588,100000,100000,137601 -8.241854,-0.202586,0.354947,-0.981115,-0.00245,-0.009743,0.099276,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-101.088554,115.823868,-49588.82031,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137580,100000,100000,137609 -8.246855,-0.179148,0.311979,-0.961096,0.001807,-0.007615,0.081184,0,0.013264,0.000282,-0.064829,0.060666,-4.759611,-104.994522,108.01194,-49404.17969,0,0,0.127668,1.040149,-0.725774,-0.023723,0.078093,-0.060383,0.089533,0.334481,0,137591,100000,100000,137598 -8.251856,-0.15742,0.264127,-0.954748,0.000743,-0.00655,0.067349,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-119.135727,103.400543,-49151.06641,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137610,100000,100000,137579 -8.256857,-0.131053,0.212613,-0.961828,0.003936,-0.007615,0.056706,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,97.541595,-49042.45313,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137610,100000,100000,137571 -8.261858,-0.10615,0.158658,-0.980139,0.000743,-0.007615,0.049257,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,103.400543,-48966.42578,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137604,100000,100000,137577 -8.266859,-0.080271,0.110318,-0.998693,0.002872,-0.007615,0.043936,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,99.494576,-48912.11719,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137608,100000,100000,137573 -8.27186,-0.061229,0.069059,-1.009436,0.000743,-0.007615,0.038615,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,103.400543,-48857.8125,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137604,100000,100000,137577 -8.276861,-0.045359,0.038785,-1.006262,0.002872,-0.007615,0.034358,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-117.182739,99.494576,-48814.36719,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137608,100000,100000,137573 -8.281862,-0.038279,0.02609,-0.994299,0.000743,-0.00655,0.029037,0,0.008525,-0.003021,-0.07147,0.057088,-4.748645,-119.135727,103.400543,-48760.05859,0,0,0.129474,1.042354,-0.724396,-0.023616,0.079995,-0.06011,0.089533,0.334481,0,137615,100000,100000,137584 -8.286863,-0.037791,0.026822,-0.981604,-0.001385,-0.009743,0.022651,0,0.004473,-0.008908,-0.072564,0.051306,-4.781736,-115.284752,96.694389,-49032.61328,0,0,0.131457,1.043312,-0.721488,-0.023576,0.077037,-0.060214,0.089533,0.334481,0,137618,100000,100000,137581 -8.291864,-0.04365,0.037564,-0.974279,-0.001385,-0.005486,0.01733,0,-0.007606,0.020257,-0.086086,0.080552,-4.721994,-147.910294,150.36525,-48368.59766,0,0,0.130634,1.042654,-0.722474,-0.023579,0.07848,-0.060296,0.089533,0.334481,0,137597,100000,100000,137602 -8.296865,-0.048777,0.0444,-0.978918,-0.004578,-0.008679,0.013073,0,-0.007606,0.020257,-0.086086,0.080552,-4.721994,-142.051346,156.224197,-48325.15234,0,0,0.130634,1.042654,-0.722474,-0.023579,0.07848,-0.060296,0.089533,0.334481,0,137585,100000,100000,137614 -8.301867,-0.050975,0.046354,-0.989904,-0.004578,-0.007615,0.010945,0,-0.005951,0.017183,-0.087077,0.083013,-4.690295,-145.823639,160.740372,-47979.91016,0,0,0.129413,1.041805,-0.72399,-0.023314,0.081127,-0.06583,0.089533,0.334481,0,137642,100000,100000,137671 -8.306868,-0.053904,0.042203,-0.99967,-0.006706,-0.009743,0.010945,0,-0.005951,0.017183,-0.087077,0.083013,-4.690295,-141.917679,164.646332,-47979.91016,0,0,0.129413,1.041805,-0.72399,-0.023314,0.081127,-0.06583,0.089533,0.334481,0,137634,100000,100000,137679 -8.311869,-0.04951,0.029508,-0.99967,-0.004578,-0.007615,0.010945,0,-0.005951,0.017183,-0.087077,0.083013,-4.690295,-145.823639,160.740372,-47979.91016,0,0,0.129413,1.041805,-0.72399,-0.023314,0.081127,-0.06583,0.089533,0.334481,0,137642,100000,100000,137671 diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/EMLReport/sL897IXghI8zmc3H8vRBKxD.mat b/controls/model/loggingAnalysis/slprj/_sfprj/EMLReport/sL897IXghI8zmc3H8vRBKxD.mat deleted file mode 100644 index 0525f07daba7714fe185e1428a497d0650c1c98c..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/EMLReport/sL897IXghI8zmc3H8vRBKxD.mat and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/info/binfo.mat b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/info/binfo.mat deleted file mode 100644 index 6fa0e5c2e0dcd0882ae2cc364479119d3741f44a..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/info/binfo.mat and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.c b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.c deleted file mode 100644 index 57f63efc7757630bf45b1ac51f17b12ba887aa79..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.c +++ /dev/null @@ -1,1605 +0,0 @@ -/* Include files */ - -#include "test_model_sfun.h" -#include "c15_test_model.h" -#define CHARTINSTANCE_CHARTNUMBER (chartInstance->chartNumber) -#define CHARTINSTANCE_INSTANCENUMBER (chartInstance->instanceNumber) -#include "test_model_sfun_debug_macros.h" -#define _SF_MEX_LISTEN_FOR_CTRL_C(S) sf_mex_listen_for_ctrl_c_with_debugger(S, sfGlobalDebugInstanceStruct); - -static void chart_debug_initialization(SimStruct *S, unsigned int - fullDebuggerInitialization); -static void chart_debug_initialize_data_addresses(SimStruct *S); -static const mxArray* sf_opaque_get_hover_data_for_msg(void *chartInstance, - int32_T msgSSID); - -/* Type Definitions */ - -/* Named Constants */ -#define CALL_EVENT (-1) - -/* Variable Declarations */ - -/* Variable Definitions */ -static real_T _sfTime_; -static const char * c15_debug_family_names[29] = { "out_z", "out_y", "out_x", - "out_yaw", "c_pid_y", "c_pid_roll", "nargin", "nargout", "set_x", "set_y", - "set_z", "set_yaw", "cur_x", "cur_y", "cur_z", "cur_phi", "cur_theta", - "cur_psi", "cur_phi_d", "cur_theta_d", "cur_psi_d", "vrpn_id", "Tc", "z_corr", - "y_cor", "x_corr", "yaw_corr", "pid_y_out", "pid_roll_out" }; - -/* Function Declarations */ -static void initialize_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance); -static void initialize_params_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance); -static void enable_c15_test_model(SFc15_test_modelInstanceStruct *chartInstance); -static void disable_c15_test_model(SFc15_test_modelInstanceStruct *chartInstance); -static void c15_update_debugger_state_c15_test_model - (SFc15_test_modelInstanceStruct *chartInstance); -static const mxArray *get_sim_state_c15_test_model - (SFc15_test_modelInstanceStruct *chartInstance); -static void set_sim_state_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_st); -static void finalize_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance); -static void sf_gateway_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance); -static void mdl_start_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance); -static void initSimStructsc15_test_model(SFc15_test_modelInstanceStruct - *chartInstance); -static void init_script_number_translation(uint32_T c15_machineNumber, uint32_T - c15_chartNumber, uint32_T c15_instanceNumber); -static const mxArray *c15_sf_marshallOut(void *chartInstanceVoid, void - *c15_inData); -static real_T c15_emlrt_marshallIn(SFc15_test_modelInstanceStruct *chartInstance, - const mxArray *c15_b_pid_roll_out, const char_T *c15_identifier); -static real_T c15_b_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_u, const emlrtMsgIdentifier *c15_parentId); -static void c15_sf_marshallIn(void *chartInstanceVoid, const mxArray - *c15_mxArrayInData, const char_T *c15_varName, void *c15_outData); -static const mxArray *c15_b_sf_marshallOut(void *chartInstanceVoid, void - *c15_inData); -static const mxArray *c15_c_sf_marshallOut(void *chartInstanceVoid, void - *c15_inData); -static int32_T c15_c_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_u, const emlrtMsgIdentifier *c15_parentId); -static void c15_b_sf_marshallIn(void *chartInstanceVoid, const mxArray - *c15_mxArrayInData, const char_T *c15_varName, void *c15_outData); -static uint8_T c15_d_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_b_is_active_c15_test_model, const char_T - *c15_identifier); -static uint8_T c15_e_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_u, const emlrtMsgIdentifier *c15_parentId); -static void init_dsm_address_info(SFc15_test_modelInstanceStruct *chartInstance); -static void init_simulink_io_address(SFc15_test_modelInstanceStruct - *chartInstance); - -/* Function Definitions */ -static void initialize_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance) -{ - if (sf_is_first_init_cond(chartInstance->S)) { - initSimStructsc15_test_model(chartInstance); - chart_debug_initialize_data_addresses(chartInstance->S); - } - - chartInstance->c15_sfEvent = CALL_EVENT; - _sfTime_ = sf_get_time(chartInstance->S); - chartInstance->c15_is_active_c15_test_model = 0U; -} - -static void initialize_params_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance) -{ - (void)chartInstance; -} - -static void enable_c15_test_model(SFc15_test_modelInstanceStruct *chartInstance) -{ - _sfTime_ = sf_get_time(chartInstance->S); -} - -static void disable_c15_test_model(SFc15_test_modelInstanceStruct *chartInstance) -{ - _sfTime_ = sf_get_time(chartInstance->S); -} - -static void c15_update_debugger_state_c15_test_model - (SFc15_test_modelInstanceStruct *chartInstance) -{ - (void)chartInstance; -} - -static const mxArray *get_sim_state_c15_test_model - (SFc15_test_modelInstanceStruct *chartInstance) -{ - const mxArray *c15_st; - const mxArray *c15_y = NULL; - real_T c15_hoistedGlobal; - const mxArray *c15_b_y = NULL; - real_T c15_b_hoistedGlobal; - const mxArray *c15_c_y = NULL; - real_T c15_c_hoistedGlobal; - const mxArray *c15_d_y = NULL; - real_T c15_d_hoistedGlobal; - const mxArray *c15_e_y = NULL; - real_T c15_e_hoistedGlobal; - const mxArray *c15_f_y = NULL; - real_T c15_f_hoistedGlobal; - const mxArray *c15_g_y = NULL; - uint8_T c15_g_hoistedGlobal; - const mxArray *c15_h_y = NULL; - c15_st = NULL; - c15_st = NULL; - c15_y = NULL; - sf_mex_assign(&c15_y, sf_mex_createcellmatrix(7, 1), false); - c15_hoistedGlobal = *chartInstance->c15_pid_roll_out; - c15_b_y = NULL; - sf_mex_assign(&c15_b_y, sf_mex_create("y", &c15_hoistedGlobal, 0, 0U, 0U, 0U, - 0), false); - sf_mex_setcell(c15_y, 0, c15_b_y); - c15_b_hoistedGlobal = *chartInstance->c15_pid_y_out; - c15_c_y = NULL; - sf_mex_assign(&c15_c_y, sf_mex_create("y", &c15_b_hoistedGlobal, 0, 0U, 0U, 0U, - 0), false); - sf_mex_setcell(c15_y, 1, c15_c_y); - c15_c_hoistedGlobal = *chartInstance->c15_x_corr; - c15_d_y = NULL; - sf_mex_assign(&c15_d_y, sf_mex_create("y", &c15_c_hoistedGlobal, 0, 0U, 0U, 0U, - 0), false); - sf_mex_setcell(c15_y, 2, c15_d_y); - c15_d_hoistedGlobal = *chartInstance->c15_y_cor; - c15_e_y = NULL; - sf_mex_assign(&c15_e_y, sf_mex_create("y", &c15_d_hoistedGlobal, 0, 0U, 0U, 0U, - 0), false); - sf_mex_setcell(c15_y, 3, c15_e_y); - c15_e_hoistedGlobal = *chartInstance->c15_yaw_corr; - c15_f_y = NULL; - sf_mex_assign(&c15_f_y, sf_mex_create("y", &c15_e_hoistedGlobal, 0, 0U, 0U, 0U, - 0), false); - sf_mex_setcell(c15_y, 4, c15_f_y); - c15_f_hoistedGlobal = *chartInstance->c15_z_corr; - c15_g_y = NULL; - sf_mex_assign(&c15_g_y, sf_mex_create("y", &c15_f_hoistedGlobal, 0, 0U, 0U, 0U, - 0), false); - sf_mex_setcell(c15_y, 5, c15_g_y); - c15_g_hoistedGlobal = chartInstance->c15_is_active_c15_test_model; - c15_h_y = NULL; - sf_mex_assign(&c15_h_y, sf_mex_create("y", &c15_g_hoistedGlobal, 3, 0U, 0U, 0U, - 0), false); - sf_mex_setcell(c15_y, 6, c15_h_y); - sf_mex_assign(&c15_st, c15_y, false); - return c15_st; -} - -static void set_sim_state_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_st) -{ - const mxArray *c15_u; - chartInstance->c15_doneDoubleBufferReInit = true; - c15_u = sf_mex_dup(c15_st); - *chartInstance->c15_pid_roll_out = c15_emlrt_marshallIn(chartInstance, - sf_mex_dup(sf_mex_getcell("pid_roll_out", c15_u, 0)), "pid_roll_out"); - *chartInstance->c15_pid_y_out = c15_emlrt_marshallIn(chartInstance, sf_mex_dup - (sf_mex_getcell("pid_y_out", c15_u, 1)), "pid_y_out"); - *chartInstance->c15_x_corr = c15_emlrt_marshallIn(chartInstance, sf_mex_dup - (sf_mex_getcell("x_corr", c15_u, 2)), "x_corr"); - *chartInstance->c15_y_cor = c15_emlrt_marshallIn(chartInstance, sf_mex_dup - (sf_mex_getcell("y_cor", c15_u, 3)), "y_cor"); - *chartInstance->c15_yaw_corr = c15_emlrt_marshallIn(chartInstance, sf_mex_dup - (sf_mex_getcell("yaw_corr", c15_u, 4)), "yaw_corr"); - *chartInstance->c15_z_corr = c15_emlrt_marshallIn(chartInstance, sf_mex_dup - (sf_mex_getcell("z_corr", c15_u, 5)), "z_corr"); - chartInstance->c15_is_active_c15_test_model = c15_d_emlrt_marshallIn - (chartInstance, sf_mex_dup(sf_mex_getcell("is_active_c15_test_model", c15_u, - 6)), "is_active_c15_test_model"); - sf_mex_destroy(&c15_u); - c15_update_debugger_state_c15_test_model(chartInstance); - sf_mex_destroy(&c15_st); -} - -static void finalize_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance) -{ - (void)chartInstance; -} - -static void sf_gateway_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance) -{ - real_T c15_hoistedGlobal; - real_T c15_b_hoistedGlobal; - real_T c15_c_hoistedGlobal; - real_T c15_d_hoistedGlobal; - real_T c15_e_hoistedGlobal; - real_T c15_f_hoistedGlobal; - real_T c15_g_hoistedGlobal; - real_T c15_h_hoistedGlobal; - real_T c15_i_hoistedGlobal; - real_T c15_j_hoistedGlobal; - real_T c15_k_hoistedGlobal; - real_T c15_l_hoistedGlobal; - real_T c15_m_hoistedGlobal; - uint32_T c15_n_hoistedGlobal; - real_T c15_o_hoistedGlobal; - real_T c15_b_set_x; - real_T c15_b_set_y; - real_T c15_b_set_z; - real_T c15_b_set_yaw; - real_T c15_b_cur_x; - real_T c15_b_cur_y; - real_T c15_b_cur_z; - real_T c15_b_cur_phi; - real_T c15_b_cur_theta; - real_T c15_b_cur_psi; - real_T c15_b_cur_phi_d; - real_T c15_b_cur_theta_d; - real_T c15_b_cur_psi_d; - uint32_T c15_b_vrpn_id; - real_T c15_b_Tc; - uint32_T c15_debug_family_var_map[29]; - real_T c15_out_z; - real_T c15_out_y; - real_T c15_out_x; - real_T c15_out_yaw; - real_T c15_c_pid_y; - real_T c15_c_pid_roll; - real_T c15_nargin = 15.0; - real_T c15_nargout = 6.0; - real_T c15_b_z_corr; - real_T c15_b_y_cor; - real_T c15_b_x_corr; - real_T c15_b_yaw_corr; - real_T c15_b_pid_y_out; - real_T c15_b_pid_roll_out; - _SFD_SYMBOL_SCOPE_PUSH(0U, 0U); - _sfTime_ = sf_get_time(chartInstance->S); - _SFD_CC_CALL(CHART_ENTER_SFUNCTION_TAG, 12U, chartInstance->c15_sfEvent); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_Tc, 14U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK((real_T)*chartInstance->c15_vrpn_id, 13U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_psi_d, 12U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_theta_d, 11U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_phi_d, 10U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_psi, 9U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_theta, 8U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_phi, 7U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_z, 6U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_y, 5U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_cur_x, 4U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_set_yaw, 3U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_set_z, 2U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_set_y, 1U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_set_x, 0U, 1U, 0U, - chartInstance->c15_sfEvent, false); - chartInstance->c15_sfEvent = CALL_EVENT; - _SFD_CC_CALL(CHART_ENTER_DURING_FUNCTION_TAG, 12U, chartInstance->c15_sfEvent); - c15_hoistedGlobal = *chartInstance->c15_set_x; - c15_b_hoistedGlobal = *chartInstance->c15_set_y; - c15_c_hoistedGlobal = *chartInstance->c15_set_z; - c15_d_hoistedGlobal = *chartInstance->c15_set_yaw; - c15_e_hoistedGlobal = *chartInstance->c15_cur_x; - c15_f_hoistedGlobal = *chartInstance->c15_cur_y; - c15_g_hoistedGlobal = *chartInstance->c15_cur_z; - c15_h_hoistedGlobal = *chartInstance->c15_cur_phi; - c15_i_hoistedGlobal = *chartInstance->c15_cur_theta; - c15_j_hoistedGlobal = *chartInstance->c15_cur_psi; - c15_k_hoistedGlobal = *chartInstance->c15_cur_phi_d; - c15_l_hoistedGlobal = *chartInstance->c15_cur_theta_d; - c15_m_hoistedGlobal = *chartInstance->c15_cur_psi_d; - c15_n_hoistedGlobal = *chartInstance->c15_vrpn_id; - c15_o_hoistedGlobal = *chartInstance->c15_Tc; - c15_b_set_x = c15_hoistedGlobal; - c15_b_set_y = c15_b_hoistedGlobal; - c15_b_set_z = c15_c_hoistedGlobal; - c15_b_set_yaw = c15_d_hoistedGlobal; - c15_b_cur_x = c15_e_hoistedGlobal; - c15_b_cur_y = c15_f_hoistedGlobal; - c15_b_cur_z = c15_g_hoistedGlobal; - c15_b_cur_phi = c15_h_hoistedGlobal; - c15_b_cur_theta = c15_i_hoistedGlobal; - c15_b_cur_psi = c15_j_hoistedGlobal; - c15_b_cur_phi_d = c15_k_hoistedGlobal; - c15_b_cur_theta_d = c15_l_hoistedGlobal; - c15_b_cur_psi_d = c15_m_hoistedGlobal; - c15_b_vrpn_id = c15_n_hoistedGlobal; - c15_b_Tc = c15_o_hoistedGlobal; - _SFD_SYMBOL_SCOPE_PUSH_EML(0U, 29U, 29U, c15_debug_family_names, - c15_debug_family_var_map); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_out_z, 0U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_out_y, 1U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_out_x, 2U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_out_yaw, 3U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_c_pid_y, 4U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_c_pid_roll, 5U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_nargin, 6U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_nargout, 7U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_set_x, 8U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_set_y, 9U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_set_z, 10U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_set_yaw, 11U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_x, 12U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_y, 13U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_z, 14U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_phi, 15U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_theta, 16U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_psi, 17U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_phi_d, 18U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_theta_d, 19U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_cur_psi_d, 20U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_vrpn_id, 21U, c15_b_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML(&c15_b_Tc, 22U, c15_sf_marshallOut); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_b_z_corr, 23U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_b_y_cor, 24U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_b_x_corr, 25U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_b_yaw_corr, 26U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_b_pid_y_out, 27U, c15_sf_marshallOut, - c15_sf_marshallIn); - _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(&c15_b_pid_roll_out, 28U, - c15_sf_marshallOut, c15_sf_marshallIn); - CV_EML_FCN(0, 0); - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 6); - c15_out_z = -1.0; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 7); - c15_out_y = -1.0; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 8); - c15_out_x = -1.0; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 9); - c15_out_yaw = -1.0; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 10); - c15_c_pid_y = -1.0; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 11); - c15_c_pid_roll = -1.0; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 13); - c_controller(c15_b_vrpn_id, c15_b_Tc, c15_b_set_x, c15_b_set_y, c15_b_set_z, - c15_b_set_yaw, c15_b_cur_x, c15_b_cur_y, c15_b_cur_z, - c15_b_cur_phi, c15_b_cur_theta, c15_b_cur_psi, c15_b_cur_phi_d, - c15_b_cur_theta_d, c15_b_cur_psi_d, &c15_out_z, &c15_out_y, - &c15_out_x, &c15_out_yaw, &c15_c_pid_y, &c15_c_pid_roll); - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 20); - c15_b_z_corr = c15_out_z; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 21); - c15_b_y_cor = c15_out_y; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 22); - c15_b_x_corr = c15_out_x; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 23); - c15_b_pid_y_out = c15_c_pid_y; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 24); - c15_b_pid_roll_out = c15_c_pid_roll; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, 25); - c15_b_yaw_corr = c15_out_yaw; - _SFD_EML_CALL(0U, chartInstance->c15_sfEvent, -25); - _SFD_SYMBOL_SCOPE_POP(); - *chartInstance->c15_z_corr = c15_b_z_corr; - *chartInstance->c15_y_cor = c15_b_y_cor; - *chartInstance->c15_x_corr = c15_b_x_corr; - *chartInstance->c15_yaw_corr = c15_b_yaw_corr; - *chartInstance->c15_pid_y_out = c15_b_pid_y_out; - *chartInstance->c15_pid_roll_out = c15_b_pid_roll_out; - _SFD_CC_CALL(EXIT_OUT_OF_FUNCTION_TAG, 12U, chartInstance->c15_sfEvent); - _SFD_SYMBOL_SCOPE_POP(); - _SFD_CHECK_FOR_STATE_INCONSISTENCY(_test_modelMachineNumber_, - chartInstance->chartNumber, chartInstance->instanceNumber); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_z_corr, 15U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_y_cor, 16U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_x_corr, 17U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_yaw_corr, 18U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_pid_y_out, 19U, 1U, 0U, - chartInstance->c15_sfEvent, false); - _SFD_DATA_RANGE_CHECK(*chartInstance->c15_pid_roll_out, 20U, 1U, 0U, - chartInstance->c15_sfEvent, false); -} - -static void mdl_start_c15_test_model(SFc15_test_modelInstanceStruct - *chartInstance) -{ - (void)chartInstance; -} - -static void initSimStructsc15_test_model(SFc15_test_modelInstanceStruct - *chartInstance) -{ - (void)chartInstance; -} - -static void init_script_number_translation(uint32_T c15_machineNumber, uint32_T - c15_chartNumber, uint32_T c15_instanceNumber) -{ - (void)c15_machineNumber; - (void)c15_chartNumber; - (void)c15_instanceNumber; -} - -static const mxArray *c15_sf_marshallOut(void *chartInstanceVoid, void - *c15_inData) -{ - const mxArray *c15_mxArrayOutData; - real_T c15_u; - const mxArray *c15_y = NULL; - SFc15_test_modelInstanceStruct *chartInstance; - chartInstance = (SFc15_test_modelInstanceStruct *)chartInstanceVoid; - c15_mxArrayOutData = NULL; - c15_mxArrayOutData = NULL; - c15_u = *(real_T *)c15_inData; - c15_y = NULL; - sf_mex_assign(&c15_y, sf_mex_create("y", &c15_u, 0, 0U, 0U, 0U, 0), false); - sf_mex_assign(&c15_mxArrayOutData, c15_y, false); - return c15_mxArrayOutData; -} - -static real_T c15_emlrt_marshallIn(SFc15_test_modelInstanceStruct *chartInstance, - const mxArray *c15_b_pid_roll_out, const char_T *c15_identifier) -{ - real_T c15_y; - emlrtMsgIdentifier c15_thisId; - c15_thisId.fIdentifier = c15_identifier; - c15_thisId.fParent = NULL; - c15_thisId.bParentIsCell = false; - c15_y = c15_b_emlrt_marshallIn(chartInstance, sf_mex_dup(c15_b_pid_roll_out), - &c15_thisId); - sf_mex_destroy(&c15_b_pid_roll_out); - return c15_y; -} - -static real_T c15_b_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_u, const emlrtMsgIdentifier *c15_parentId) -{ - real_T c15_y; - real_T c15_d0; - (void)chartInstance; - sf_mex_import(c15_parentId, sf_mex_dup(c15_u), &c15_d0, 1, 0, 0U, 0, 0U, 0); - c15_y = c15_d0; - sf_mex_destroy(&c15_u); - return c15_y; -} - -static void c15_sf_marshallIn(void *chartInstanceVoid, const mxArray - *c15_mxArrayInData, const char_T *c15_varName, void *c15_outData) -{ - const mxArray *c15_b_pid_roll_out; - const char_T *c15_identifier; - emlrtMsgIdentifier c15_thisId; - real_T c15_y; - SFc15_test_modelInstanceStruct *chartInstance; - chartInstance = (SFc15_test_modelInstanceStruct *)chartInstanceVoid; - c15_b_pid_roll_out = sf_mex_dup(c15_mxArrayInData); - c15_identifier = c15_varName; - c15_thisId.fIdentifier = c15_identifier; - c15_thisId.fParent = NULL; - c15_thisId.bParentIsCell = false; - c15_y = c15_b_emlrt_marshallIn(chartInstance, sf_mex_dup(c15_b_pid_roll_out), - &c15_thisId); - sf_mex_destroy(&c15_b_pid_roll_out); - *(real_T *)c15_outData = c15_y; - sf_mex_destroy(&c15_mxArrayInData); -} - -static const mxArray *c15_b_sf_marshallOut(void *chartInstanceVoid, void - *c15_inData) -{ - const mxArray *c15_mxArrayOutData; - uint32_T c15_u; - const mxArray *c15_y = NULL; - SFc15_test_modelInstanceStruct *chartInstance; - chartInstance = (SFc15_test_modelInstanceStruct *)chartInstanceVoid; - c15_mxArrayOutData = NULL; - c15_mxArrayOutData = NULL; - c15_u = *(uint32_T *)c15_inData; - c15_y = NULL; - sf_mex_assign(&c15_y, sf_mex_create("y", &c15_u, 7, 0U, 0U, 0U, 0), false); - sf_mex_assign(&c15_mxArrayOutData, c15_y, false); - return c15_mxArrayOutData; -} - -const mxArray *sf_c15_test_model_get_eml_resolved_functions_info(void) -{ - const mxArray *c15_nameCaptureInfo = NULL; - c15_nameCaptureInfo = NULL; - sf_mex_assign(&c15_nameCaptureInfo, sf_mex_create("nameCaptureInfo", NULL, 0, - 0U, 1U, 0U, 2, 0, 1), false); - return c15_nameCaptureInfo; -} - -static const mxArray *c15_c_sf_marshallOut(void *chartInstanceVoid, void - *c15_inData) -{ - const mxArray *c15_mxArrayOutData; - int32_T c15_u; - const mxArray *c15_y = NULL; - SFc15_test_modelInstanceStruct *chartInstance; - chartInstance = (SFc15_test_modelInstanceStruct *)chartInstanceVoid; - c15_mxArrayOutData = NULL; - c15_mxArrayOutData = NULL; - c15_u = *(int32_T *)c15_inData; - c15_y = NULL; - sf_mex_assign(&c15_y, sf_mex_create("y", &c15_u, 6, 0U, 0U, 0U, 0), false); - sf_mex_assign(&c15_mxArrayOutData, c15_y, false); - return c15_mxArrayOutData; -} - -static int32_T c15_c_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_u, const emlrtMsgIdentifier *c15_parentId) -{ - int32_T c15_y; - int32_T c15_i0; - (void)chartInstance; - sf_mex_import(c15_parentId, sf_mex_dup(c15_u), &c15_i0, 1, 6, 0U, 0, 0U, 0); - c15_y = c15_i0; - sf_mex_destroy(&c15_u); - return c15_y; -} - -static void c15_b_sf_marshallIn(void *chartInstanceVoid, const mxArray - *c15_mxArrayInData, const char_T *c15_varName, void *c15_outData) -{ - const mxArray *c15_b_sfEvent; - const char_T *c15_identifier; - emlrtMsgIdentifier c15_thisId; - int32_T c15_y; - SFc15_test_modelInstanceStruct *chartInstance; - chartInstance = (SFc15_test_modelInstanceStruct *)chartInstanceVoid; - c15_b_sfEvent = sf_mex_dup(c15_mxArrayInData); - c15_identifier = c15_varName; - c15_thisId.fIdentifier = c15_identifier; - c15_thisId.fParent = NULL; - c15_thisId.bParentIsCell = false; - c15_y = c15_c_emlrt_marshallIn(chartInstance, sf_mex_dup(c15_b_sfEvent), - &c15_thisId); - sf_mex_destroy(&c15_b_sfEvent); - *(int32_T *)c15_outData = c15_y; - sf_mex_destroy(&c15_mxArrayInData); -} - -static uint8_T c15_d_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_b_is_active_c15_test_model, const char_T - *c15_identifier) -{ - uint8_T c15_y; - emlrtMsgIdentifier c15_thisId; - c15_thisId.fIdentifier = c15_identifier; - c15_thisId.fParent = NULL; - c15_thisId.bParentIsCell = false; - c15_y = c15_e_emlrt_marshallIn(chartInstance, sf_mex_dup - (c15_b_is_active_c15_test_model), &c15_thisId); - sf_mex_destroy(&c15_b_is_active_c15_test_model); - return c15_y; -} - -static uint8_T c15_e_emlrt_marshallIn(SFc15_test_modelInstanceStruct - *chartInstance, const mxArray *c15_u, const emlrtMsgIdentifier *c15_parentId) -{ - uint8_T c15_y; - uint8_T c15_u0; - (void)chartInstance; - sf_mex_import(c15_parentId, sf_mex_dup(c15_u), &c15_u0, 1, 3, 0U, 0, 0U, 0); - c15_y = c15_u0; - sf_mex_destroy(&c15_u); - return c15_y; -} - -static void init_dsm_address_info(SFc15_test_modelInstanceStruct *chartInstance) -{ - (void)chartInstance; -} - -static void init_simulink_io_address(SFc15_test_modelInstanceStruct - *chartInstance) -{ - chartInstance->c15_set_x = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 0); - chartInstance->c15_z_corr = (real_T *)ssGetOutputPortSignal_wrapper - (chartInstance->S, 1); - chartInstance->c15_set_y = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 1); - chartInstance->c15_set_z = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 2); - chartInstance->c15_set_yaw = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 3); - chartInstance->c15_cur_x = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 4); - chartInstance->c15_cur_y = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 5); - chartInstance->c15_cur_z = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 6); - chartInstance->c15_cur_phi = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 7); - chartInstance->c15_cur_theta = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 8); - chartInstance->c15_cur_psi = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 9); - chartInstance->c15_cur_phi_d = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 10); - chartInstance->c15_cur_theta_d = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 11); - chartInstance->c15_cur_psi_d = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 12); - chartInstance->c15_y_cor = (real_T *)ssGetOutputPortSignal_wrapper - (chartInstance->S, 2); - chartInstance->c15_x_corr = (real_T *)ssGetOutputPortSignal_wrapper - (chartInstance->S, 3); - chartInstance->c15_yaw_corr = (real_T *)ssGetOutputPortSignal_wrapper - (chartInstance->S, 4); - chartInstance->c15_vrpn_id = (uint32_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 13); - chartInstance->c15_pid_y_out = (real_T *)ssGetOutputPortSignal_wrapper - (chartInstance->S, 5); - chartInstance->c15_pid_roll_out = (real_T *)ssGetOutputPortSignal_wrapper - (chartInstance->S, 6); - chartInstance->c15_Tc = (real_T *)ssGetInputPortSignal_wrapper - (chartInstance->S, 14); -} - -/* SFunction Glue Code */ -#ifdef utFree -#undef utFree -#endif - -#ifdef utMalloc -#undef utMalloc -#endif - -#ifdef __cplusplus - -extern "C" void *utMalloc(size_t size); -extern "C" void utFree(void*); - -#else - -extern void *utMalloc(size_t size); -extern void utFree(void*); - -#endif - -void sf_c15_test_model_get_check_sum(mxArray *plhs[]) -{ - ((real_T *)mxGetPr((plhs[0])))[0] = (real_T)(736349010U); - ((real_T *)mxGetPr((plhs[0])))[1] = (real_T)(2782398305U); - ((real_T *)mxGetPr((plhs[0])))[2] = (real_T)(65662726U); - ((real_T *)mxGetPr((plhs[0])))[3] = (real_T)(769147733U); -} - -mxArray* sf_c15_test_model_get_post_codegen_info(void); -mxArray *sf_c15_test_model_get_autoinheritance_info(void) -{ - const char *autoinheritanceFields[] = { "checksum", "inputs", "parameters", - "outputs", "locals", "postCodegenInfo" }; - - mxArray *mxAutoinheritanceInfo = mxCreateStructMatrix(1, 1, sizeof - (autoinheritanceFields)/sizeof(autoinheritanceFields[0]), - autoinheritanceFields); - - { - mxArray *mxChecksum = mxCreateString("NhviQufdzoJMzgXQ3dS4TB"); - mxSetField(mxAutoinheritanceInfo,0,"checksum",mxChecksum); - } - - { - const char *dataFields[] = { "size", "type", "complexity" }; - - mxArray *mxData = mxCreateStructMatrix(1,15,3,dataFields); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,0,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,0,"type",mxType); - } - - mxSetField(mxData,0,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,1,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,1,"type",mxType); - } - - mxSetField(mxData,1,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,2,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,2,"type",mxType); - } - - mxSetField(mxData,2,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,3,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,3,"type",mxType); - } - - mxSetField(mxData,3,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,4,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,4,"type",mxType); - } - - mxSetField(mxData,4,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,5,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,5,"type",mxType); - } - - mxSetField(mxData,5,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,6,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,6,"type",mxType); - } - - mxSetField(mxData,6,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,7,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,7,"type",mxType); - } - - mxSetField(mxData,7,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,8,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,8,"type",mxType); - } - - mxSetField(mxData,8,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,9,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,9,"type",mxType); - } - - mxSetField(mxData,9,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,10,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,10,"type",mxType); - } - - mxSetField(mxData,10,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,11,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,11,"type",mxType); - } - - mxSetField(mxData,11,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,12,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,12,"type",mxType); - } - - mxSetField(mxData,12,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,13,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(7)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,13,"type",mxType); - } - - mxSetField(mxData,13,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,14,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,14,"type",mxType); - } - - mxSetField(mxData,14,"complexity",mxCreateDoubleScalar(0)); - mxSetField(mxAutoinheritanceInfo,0,"inputs",mxData); - } - - { - mxSetField(mxAutoinheritanceInfo,0,"parameters",mxCreateDoubleMatrix(0,0, - mxREAL)); - } - - { - const char *dataFields[] = { "size", "type", "complexity" }; - - mxArray *mxData = mxCreateStructMatrix(1,6,3,dataFields); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,0,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,0,"type",mxType); - } - - mxSetField(mxData,0,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,1,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,1,"type",mxType); - } - - mxSetField(mxData,1,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,2,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,2,"type",mxType); - } - - mxSetField(mxData,2,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,3,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,3,"type",mxType); - } - - mxSetField(mxData,3,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,4,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,4,"type",mxType); - } - - mxSetField(mxData,4,"complexity",mxCreateDoubleScalar(0)); - - { - mxArray *mxSize = mxCreateDoubleMatrix(1,0,mxREAL); - double *pr = mxGetPr(mxSize); - mxSetField(mxData,5,"size",mxSize); - } - - { - const char *typeFields[] = { "base", "fixpt", "isFixedPointType" }; - - mxArray *mxType = mxCreateStructMatrix(1,1,sizeof(typeFields)/sizeof - (typeFields[0]),typeFields); - mxSetField(mxType,0,"base",mxCreateDoubleScalar(10)); - mxSetField(mxType,0,"fixpt",mxCreateDoubleMatrix(0,0,mxREAL)); - mxSetField(mxType,0,"isFixedPointType",mxCreateDoubleScalar(0)); - mxSetField(mxData,5,"type",mxType); - } - - mxSetField(mxData,5,"complexity",mxCreateDoubleScalar(0)); - mxSetField(mxAutoinheritanceInfo,0,"outputs",mxData); - } - - { - mxSetField(mxAutoinheritanceInfo,0,"locals",mxCreateDoubleMatrix(0,0,mxREAL)); - } - - { - mxArray* mxPostCodegenInfo = sf_c15_test_model_get_post_codegen_info(); - mxSetField(mxAutoinheritanceInfo,0,"postCodegenInfo",mxPostCodegenInfo); - } - - return(mxAutoinheritanceInfo); -} - -mxArray *sf_c15_test_model_third_party_uses_info(void) -{ - mxArray * mxcell3p = mxCreateCellMatrix(1,0); - return(mxcell3p); -} - -mxArray *sf_c15_test_model_jit_fallback_info(void) -{ - const char *infoFields[] = { "fallbackType", "fallbackReason", - "hiddenFallbackType", "hiddenFallbackReason", "incompatibleSymbol" }; - - mxArray *mxInfo = mxCreateStructMatrix(1, 1, 5, infoFields); - mxArray *fallbackType = mxCreateString("late"); - mxArray *fallbackReason = mxCreateString("ir_function_calls"); - mxArray *hiddenFallbackType = mxCreateString(""); - mxArray *hiddenFallbackReason = mxCreateString(""); - mxArray *incompatibleSymbol = mxCreateString("c_controller"); - mxSetField(mxInfo, 0, infoFields[0], fallbackType); - mxSetField(mxInfo, 0, infoFields[1], fallbackReason); - mxSetField(mxInfo, 0, infoFields[2], hiddenFallbackType); - mxSetField(mxInfo, 0, infoFields[3], hiddenFallbackReason); - mxSetField(mxInfo, 0, infoFields[4], incompatibleSymbol); - return mxInfo; -} - -mxArray *sf_c15_test_model_updateBuildInfo_args_info(void) -{ - mxArray *mxBIArgs = mxCreateCellMatrix(1,0); - return mxBIArgs; -} - -mxArray* sf_c15_test_model_get_post_codegen_info(void) -{ - const char* fieldNames[] = { "exportedFunctionsUsedByThisChart", - "exportedFunctionsChecksum" }; - - mwSize dims[2] = { 1, 1 }; - - mxArray* mxPostCodegenInfo = mxCreateStructArray(2, dims, sizeof(fieldNames)/ - sizeof(fieldNames[0]), fieldNames); - - { - mxArray* mxExportedFunctionsChecksum = mxCreateString(""); - mwSize exp_dims[2] = { 0, 1 }; - - mxArray* mxExportedFunctionsUsedByThisChart = mxCreateCellArray(2, exp_dims); - mxSetField(mxPostCodegenInfo, 0, "exportedFunctionsUsedByThisChart", - mxExportedFunctionsUsedByThisChart); - mxSetField(mxPostCodegenInfo, 0, "exportedFunctionsChecksum", - mxExportedFunctionsChecksum); - } - - return mxPostCodegenInfo; -} - -static const mxArray *sf_get_sim_state_info_c15_test_model(void) -{ - const char *infoFields[] = { "chartChecksum", "varInfo" }; - - mxArray *mxInfo = mxCreateStructMatrix(1, 1, 2, infoFields); - const char *infoEncStr[] = { - "100 S1x7'type','srcId','name','auxInfo'{{M[1],M[23],T\"pid_roll_out\",},{M[1],M[22],T\"pid_y_out\",},{M[1],M[19],T\"x_corr\",},{M[1],M[18],T\"y_cor\",},{M[1],M[20],T\"yaw_corr\",},{M[1],M[5],T\"z_corr\",},{M[8],M[0],T\"is_active_c15_test_model\",}}" - }; - - mxArray *mxVarInfo = sf_mex_decode_encoded_mx_struct_array(infoEncStr, 7, 10); - mxArray *mxChecksum = mxCreateDoubleMatrix(1, 4, mxREAL); - sf_c15_test_model_get_check_sum(&mxChecksum); - mxSetField(mxInfo, 0, infoFields[0], mxChecksum); - mxSetField(mxInfo, 0, infoFields[1], mxVarInfo); - return mxInfo; -} - -static void chart_debug_initialization(SimStruct *S, unsigned int - fullDebuggerInitialization) -{ - if (!sim_mode_is_rtw_gen(S)) { - SFc15_test_modelInstanceStruct *chartInstance = - (SFc15_test_modelInstanceStruct *)sf_get_chart_instance_ptr(S); - if (ssIsFirstInitCond(S) && fullDebuggerInitialization==1) { - /* do this only if simulation is starting */ - { - unsigned int chartAlreadyPresent; - chartAlreadyPresent = sf_debug_initialize_chart - (sfGlobalDebugInstanceStruct, - _test_modelMachineNumber_, - 15, - 1, - 1, - 0, - 21, - 0, - 0, - 0, - 0, - 0, - &chartInstance->chartNumber, - &chartInstance->instanceNumber, - (void *)S); - - /* Each instance must initialize its own list of scripts */ - init_script_number_translation(_test_modelMachineNumber_, - chartInstance->chartNumber,chartInstance->instanceNumber); - if (chartAlreadyPresent==0) { - /* this is the first instance */ - sf_debug_set_chart_disable_implicit_casting - (sfGlobalDebugInstanceStruct,_test_modelMachineNumber_, - chartInstance->chartNumber,1); - sf_debug_set_chart_event_thresholds(sfGlobalDebugInstanceStruct, - _test_modelMachineNumber_, - chartInstance->chartNumber, - 0, - 0, - 0); - _SFD_SET_DATA_PROPS(0,1,1,0,"set_x"); - _SFD_SET_DATA_PROPS(1,1,1,0,"set_y"); - _SFD_SET_DATA_PROPS(2,1,1,0,"set_z"); - _SFD_SET_DATA_PROPS(3,1,1,0,"set_yaw"); - _SFD_SET_DATA_PROPS(4,1,1,0,"cur_x"); - _SFD_SET_DATA_PROPS(5,1,1,0,"cur_y"); - _SFD_SET_DATA_PROPS(6,1,1,0,"cur_z"); - _SFD_SET_DATA_PROPS(7,1,1,0,"cur_phi"); - _SFD_SET_DATA_PROPS(8,1,1,0,"cur_theta"); - _SFD_SET_DATA_PROPS(9,1,1,0,"cur_psi"); - _SFD_SET_DATA_PROPS(10,1,1,0,"cur_phi_d"); - _SFD_SET_DATA_PROPS(11,1,1,0,"cur_theta_d"); - _SFD_SET_DATA_PROPS(12,1,1,0,"cur_psi_d"); - _SFD_SET_DATA_PROPS(13,1,1,0,"vrpn_id"); - _SFD_SET_DATA_PROPS(14,1,1,0,"Tc"); - _SFD_SET_DATA_PROPS(15,2,0,1,"z_corr"); - _SFD_SET_DATA_PROPS(16,2,0,1,"y_cor"); - _SFD_SET_DATA_PROPS(17,2,0,1,"x_corr"); - _SFD_SET_DATA_PROPS(18,2,0,1,"yaw_corr"); - _SFD_SET_DATA_PROPS(19,2,0,1,"pid_y_out"); - _SFD_SET_DATA_PROPS(20,2,0,1,"pid_roll_out"); - _SFD_STATE_INFO(0,0,2); - _SFD_CH_SUBSTATE_COUNT(0); - _SFD_CH_SUBSTATE_DECOMP(0); - } - - _SFD_CV_INIT_CHART(0,0,0,0); - - { - _SFD_CV_INIT_STATE(0,0,0,0,0,0,NULL,NULL); - } - - _SFD_CV_INIT_TRANS(0,0,NULL,NULL,0,NULL); - - /* Initialization of MATLAB Function Model Coverage */ - _SFD_CV_INIT_EML(0,1,1,0,0,0,0,0,0,0,0,0); - _SFD_CV_INIT_EML_FCN(0,0,"eML_blk_kernel",0,-1,834); - _SFD_SET_DATA_COMPILED_PROPS(0,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(1,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(2,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(3,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(4,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(5,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(6,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(7,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(8,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(9,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(10,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(11,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(12,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(13,SF_UINT32,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_b_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(14,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)NULL); - _SFD_SET_DATA_COMPILED_PROPS(15,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)c15_sf_marshallIn); - _SFD_SET_DATA_COMPILED_PROPS(16,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)c15_sf_marshallIn); - _SFD_SET_DATA_COMPILED_PROPS(17,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)c15_sf_marshallIn); - _SFD_SET_DATA_COMPILED_PROPS(18,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)c15_sf_marshallIn); - _SFD_SET_DATA_COMPILED_PROPS(19,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)c15_sf_marshallIn); - _SFD_SET_DATA_COMPILED_PROPS(20,SF_DOUBLE,0,NULL,0,0,0,0.0,1.0,0,0, - (MexFcnForType)c15_sf_marshallOut,(MexInFcnForType)c15_sf_marshallIn); - } - } else { - sf_debug_reset_current_state_configuration(sfGlobalDebugInstanceStruct, - _test_modelMachineNumber_,chartInstance->chartNumber, - chartInstance->instanceNumber); - } - } -} - -static void chart_debug_initialize_data_addresses(SimStruct *S) -{ - if (!sim_mode_is_rtw_gen(S)) { - SFc15_test_modelInstanceStruct *chartInstance = - (SFc15_test_modelInstanceStruct *)sf_get_chart_instance_ptr(S); - if (ssIsFirstInitCond(S)) { - /* do this only if simulation is starting and after we know the addresses of all data */ - { - _SFD_SET_DATA_VALUE_PTR(0U, chartInstance->c15_set_x); - _SFD_SET_DATA_VALUE_PTR(15U, chartInstance->c15_z_corr); - _SFD_SET_DATA_VALUE_PTR(1U, chartInstance->c15_set_y); - _SFD_SET_DATA_VALUE_PTR(2U, chartInstance->c15_set_z); - _SFD_SET_DATA_VALUE_PTR(3U, chartInstance->c15_set_yaw); - _SFD_SET_DATA_VALUE_PTR(4U, chartInstance->c15_cur_x); - _SFD_SET_DATA_VALUE_PTR(5U, chartInstance->c15_cur_y); - _SFD_SET_DATA_VALUE_PTR(6U, chartInstance->c15_cur_z); - _SFD_SET_DATA_VALUE_PTR(7U, chartInstance->c15_cur_phi); - _SFD_SET_DATA_VALUE_PTR(8U, chartInstance->c15_cur_theta); - _SFD_SET_DATA_VALUE_PTR(9U, chartInstance->c15_cur_psi); - _SFD_SET_DATA_VALUE_PTR(10U, chartInstance->c15_cur_phi_d); - _SFD_SET_DATA_VALUE_PTR(11U, chartInstance->c15_cur_theta_d); - _SFD_SET_DATA_VALUE_PTR(12U, chartInstance->c15_cur_psi_d); - _SFD_SET_DATA_VALUE_PTR(16U, chartInstance->c15_y_cor); - _SFD_SET_DATA_VALUE_PTR(17U, chartInstance->c15_x_corr); - _SFD_SET_DATA_VALUE_PTR(18U, chartInstance->c15_yaw_corr); - _SFD_SET_DATA_VALUE_PTR(13U, chartInstance->c15_vrpn_id); - _SFD_SET_DATA_VALUE_PTR(19U, chartInstance->c15_pid_y_out); - _SFD_SET_DATA_VALUE_PTR(20U, chartInstance->c15_pid_roll_out); - _SFD_SET_DATA_VALUE_PTR(14U, chartInstance->c15_Tc); - } - } - } -} - -static const char* sf_get_instance_specialization(void) -{ - return "sL897IXghI8zmc3H8vRBKxD"; -} - -static void sf_opaque_initialize_c15_test_model(void *chartInstanceVar) -{ - chart_debug_initialization(((SFc15_test_modelInstanceStruct*) chartInstanceVar) - ->S,0); - initialize_params_c15_test_model((SFc15_test_modelInstanceStruct*) - chartInstanceVar); - initialize_c15_test_model((SFc15_test_modelInstanceStruct*) chartInstanceVar); -} - -static void sf_opaque_enable_c15_test_model(void *chartInstanceVar) -{ - enable_c15_test_model((SFc15_test_modelInstanceStruct*) chartInstanceVar); -} - -static void sf_opaque_disable_c15_test_model(void *chartInstanceVar) -{ - disable_c15_test_model((SFc15_test_modelInstanceStruct*) chartInstanceVar); -} - -static void sf_opaque_gateway_c15_test_model(void *chartInstanceVar) -{ - sf_gateway_c15_test_model((SFc15_test_modelInstanceStruct*) chartInstanceVar); -} - -static const mxArray* sf_opaque_get_sim_state_c15_test_model(SimStruct* S) -{ - return get_sim_state_c15_test_model((SFc15_test_modelInstanceStruct *) - sf_get_chart_instance_ptr(S)); /* raw sim ctx */ -} - -static void sf_opaque_set_sim_state_c15_test_model(SimStruct* S, const mxArray - *st) -{ - set_sim_state_c15_test_model((SFc15_test_modelInstanceStruct*) - sf_get_chart_instance_ptr(S), st); -} - -static void sf_opaque_terminate_c15_test_model(void *chartInstanceVar) -{ - if (chartInstanceVar!=NULL) { - SimStruct *S = ((SFc15_test_modelInstanceStruct*) chartInstanceVar)->S; - if (sim_mode_is_rtw_gen(S) || sim_mode_is_external(S)) { - sf_clear_rtw_identifier(S); - unload_test_model_optimization_info(); - } - - finalize_c15_test_model((SFc15_test_modelInstanceStruct*) chartInstanceVar); - utFree(chartInstanceVar); - if (ssGetUserData(S)!= NULL) { - sf_free_ChartRunTimeInfo(S); - } - - ssSetUserData(S,NULL); - } -} - -static void sf_opaque_init_subchart_simstructs(void *chartInstanceVar) -{ - initSimStructsc15_test_model((SFc15_test_modelInstanceStruct*) - chartInstanceVar); -} - -extern unsigned int sf_machine_global_initializer_called(void); -static void mdlProcessParameters_c15_test_model(SimStruct *S) -{ - int i; - for (i=0;i<ssGetNumRunTimeParams(S);i++) { - if (ssGetSFcnParamTunable(S,i)) { - ssUpdateDlgParamAsRunTimeParam(S,i); - } - } - - if (sf_machine_global_initializer_called()) { - initialize_params_c15_test_model((SFc15_test_modelInstanceStruct*) - sf_get_chart_instance_ptr(S)); - } -} - -static void mdlSetWorkWidths_c15_test_model(SimStruct *S) -{ - /* Set overwritable ports for inplace optimization */ - ssSetStatesModifiedOnlyInUpdate(S, 1); - ssMdlUpdateIsEmpty(S, 1); - if (sim_mode_is_rtw_gen(S) || sim_mode_is_external(S)) { - mxArray *infoStruct = load_test_model_optimization_info(sim_mode_is_rtw_gen - (S), sim_mode_is_modelref_sim(S), sim_mode_is_external(S)); - int_T chartIsInlinable = - (int_T)sf_is_chart_inlinable(sf_get_instance_specialization(),infoStruct, - 15); - ssSetStateflowIsInlinable(S,chartIsInlinable); - ssSetRTWCG(S,1); - ssSetEnableFcnIsTrivial(S,1); - ssSetDisableFcnIsTrivial(S,1); - ssSetNotMultipleInlinable(S,sf_rtw_info_uint_prop - (sf_get_instance_specialization(),infoStruct,15, - "gatewayCannotBeInlinedMultipleTimes")); - sf_set_chart_accesses_machine_info(S, sf_get_instance_specialization(), - infoStruct, 15); - sf_update_buildInfo(S, sf_get_instance_specialization(),infoStruct,15); - if (chartIsInlinable) { - ssSetInputPortOptimOpts(S, 0, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 1, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 2, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 3, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 4, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 5, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 6, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 7, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 8, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 9, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 10, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 11, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 12, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 13, SS_REUSABLE_AND_LOCAL); - ssSetInputPortOptimOpts(S, 14, SS_REUSABLE_AND_LOCAL); - sf_mark_chart_expressionable_inputs(S,sf_get_instance_specialization(), - infoStruct,15,15); - sf_mark_chart_reusable_outputs(S,sf_get_instance_specialization(), - infoStruct,15,6); - } - - { - unsigned int outPortIdx; - for (outPortIdx=1; outPortIdx<=6; ++outPortIdx) { - ssSetOutputPortOptimizeInIR(S, outPortIdx, 1U); - } - } - - { - unsigned int inPortIdx; - for (inPortIdx=0; inPortIdx < 15; ++inPortIdx) { - ssSetInputPortOptimizeInIR(S, inPortIdx, 1U); - } - } - - sf_set_rtw_dwork_info(S,sf_get_instance_specialization(),infoStruct,15); - sf_register_codegen_names_for_scoped_functions_defined_by_chart(S); - ssSetHasSubFunctions(S,!(chartIsInlinable)); - } else { - } - - ssSetOptions(S,ssGetOptions(S)|SS_OPTION_WORKS_WITH_CODE_REUSE); - ssSetChecksum0(S,(4110738750U)); - ssSetChecksum1(S,(2169561455U)); - ssSetChecksum2(S,(2341209886U)); - ssSetChecksum3(S,(751006734U)); - ssSetmdlDerivatives(S, NULL); - ssSetExplicitFCSSCtrl(S,1); - ssSetStateSemanticsClassicAndSynchronous(S, true); - ssSupportsMultipleExecInstances(S,1); -} - -static void mdlRTW_c15_test_model(SimStruct *S) -{ - if (sim_mode_is_rtw_gen(S)) { - ssWriteRTWStrParam(S, "StateflowChartType", "Embedded MATLAB"); - } -} - -static void mdlStart_c15_test_model(SimStruct *S) -{ - SFc15_test_modelInstanceStruct *chartInstance; - chartInstance = (SFc15_test_modelInstanceStruct *)utMalloc(sizeof - (SFc15_test_modelInstanceStruct)); - if (chartInstance==NULL) { - sf_mex_error_message("Could not allocate memory for chart instance."); - } - - memset(chartInstance, 0, sizeof(SFc15_test_modelInstanceStruct)); - chartInstance->chartInfo.chartInstance = chartInstance; - chartInstance->chartInfo.isEMLChart = 1; - chartInstance->chartInfo.chartInitialized = 0; - chartInstance->chartInfo.sFunctionGateway = sf_opaque_gateway_c15_test_model; - chartInstance->chartInfo.initializeChart = sf_opaque_initialize_c15_test_model; - chartInstance->chartInfo.terminateChart = sf_opaque_terminate_c15_test_model; - chartInstance->chartInfo.enableChart = sf_opaque_enable_c15_test_model; - chartInstance->chartInfo.disableChart = sf_opaque_disable_c15_test_model; - chartInstance->chartInfo.getSimState = sf_opaque_get_sim_state_c15_test_model; - chartInstance->chartInfo.setSimState = sf_opaque_set_sim_state_c15_test_model; - chartInstance->chartInfo.getSimStateInfo = - sf_get_sim_state_info_c15_test_model; - chartInstance->chartInfo.zeroCrossings = NULL; - chartInstance->chartInfo.outputs = NULL; - chartInstance->chartInfo.derivatives = NULL; - chartInstance->chartInfo.mdlRTW = mdlRTW_c15_test_model; - chartInstance->chartInfo.mdlStart = mdlStart_c15_test_model; - chartInstance->chartInfo.mdlSetWorkWidths = mdlSetWorkWidths_c15_test_model; - chartInstance->chartInfo.callGetHoverDataForMsg = NULL; - chartInstance->chartInfo.extModeExec = NULL; - chartInstance->chartInfo.restoreLastMajorStepConfiguration = NULL; - chartInstance->chartInfo.restoreBeforeLastMajorStepConfiguration = NULL; - chartInstance->chartInfo.storeCurrentConfiguration = NULL; - chartInstance->chartInfo.callAtomicSubchartUserFcn = NULL; - chartInstance->chartInfo.callAtomicSubchartAutoFcn = NULL; - chartInstance->chartInfo.debugInstance = sfGlobalDebugInstanceStruct; - chartInstance->S = S; - sf_init_ChartRunTimeInfo(S, &(chartInstance->chartInfo), false, 0); - init_dsm_address_info(chartInstance); - init_simulink_io_address(chartInstance); - if (!sim_mode_is_rtw_gen(S)) { - } - - chart_debug_initialization(S,1); - mdl_start_c15_test_model(chartInstance); -} - -void c15_test_model_method_dispatcher(SimStruct *S, int_T method, void *data) -{ - switch (method) { - case SS_CALL_MDL_START: - mdlStart_c15_test_model(S); - break; - - case SS_CALL_MDL_SET_WORK_WIDTHS: - mdlSetWorkWidths_c15_test_model(S); - break; - - case SS_CALL_MDL_PROCESS_PARAMETERS: - mdlProcessParameters_c15_test_model(S); - break; - - default: - /* Unhandled method */ - sf_mex_error_message("Stateflow Internal Error:\n" - "Error calling c15_test_model_method_dispatcher.\n" - "Can't handle method %d.\n", method); - break; - } -} diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.h b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.h deleted file mode 100644 index 4286ef7247286afaca46e93b22a25d271bb1744e..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.h +++ /dev/null @@ -1,62 +0,0 @@ -#ifndef __c15_test_model_h__ -#define __c15_test_model_h__ - -/* Include files */ -#include "sf_runtime/sfc_sf.h" -#include "sf_runtime/sfc_mex.h" -#include "rtwtypes.h" -#include "multiword_types.h" - -/* Type Definitions */ -#ifndef typedef_SFc15_test_modelInstanceStruct -#define typedef_SFc15_test_modelInstanceStruct - -typedef struct { - SimStruct *S; - ChartInfoStruct chartInfo; - uint32_T chartNumber; - uint32_T instanceNumber; - int32_T c15_sfEvent; - boolean_T c15_doneDoubleBufferReInit; - uint8_T c15_is_active_c15_test_model; - real_T *c15_set_x; - real_T *c15_z_corr; - real_T *c15_set_y; - real_T *c15_set_z; - real_T *c15_set_yaw; - real_T *c15_cur_x; - real_T *c15_cur_y; - real_T *c15_cur_z; - real_T *c15_cur_phi; - real_T *c15_cur_theta; - real_T *c15_cur_psi; - real_T *c15_cur_phi_d; - real_T *c15_cur_theta_d; - real_T *c15_cur_psi_d; - real_T *c15_y_cor; - real_T *c15_x_corr; - real_T *c15_yaw_corr; - uint32_T *c15_vrpn_id; - real_T *c15_pid_y_out; - real_T *c15_pid_roll_out; - real_T *c15_Tc; -} SFc15_test_modelInstanceStruct; - -#endif /*typedef_SFc15_test_modelInstanceStruct*/ - -/* Named Constants */ - -/* Variable Declarations */ -extern struct SfDebugInstanceStruct *sfGlobalDebugInstanceStruct; - -/* Variable Definitions */ - -/* Function Declarations */ -extern const mxArray *sf_c15_test_model_get_eml_resolved_functions_info(void); - -/* Function Definitions */ -extern void sf_c15_test_model_get_check_sum(mxArray *plhs[]); -extern void c15_test_model_method_dispatcher(SimStruct *S, int_T method, void - *data); - -#endif diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.obj deleted file mode 100644 index de1df7ac2e6eb114b8c3ea994643d2e6721d041b..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c_controller.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c_controller.obj deleted file mode 100644 index 68e238309af81c569d3346a105eaba55a02dbe5b..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c_controller.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/ji/late_c15_sL897IXghI8zmc3H8vRBKxD.mat b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/ji/late_c15_sL897IXghI8zmc3H8vRBKxD.mat deleted file mode 100644 index 97f6b2f0f5d0642552033d2d960abd086de67d00..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/ji/late_c15_sL897IXghI8zmc3H8vRBKxD.mat and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/multiword_types.h b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/multiword_types.h deleted file mode 100644 index 5aad425d0f2dc5f80df42e19bd9e1388dbd58f24..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/multiword_types.h +++ /dev/null @@ -1,283 +0,0 @@ -#ifndef MULTIWORD_TYPES_H -#define MULTIWORD_TYPES_H -#include "rtwtypes.h" - -/* - * MultiWord supporting definitions - */ -typedef long long longlong_T; - -/* - * MultiWord types - */ -typedef struct { - uint64_T chunks[2]; -} int128m_T; - -typedef struct { - int128m_T re; - int128m_T im; -} cint128m_T; - -typedef struct { - uint64_T chunks[2]; -} uint128m_T; - -typedef struct { - uint128m_T re; - uint128m_T im; -} cuint128m_T; - -typedef struct { - uint64_T chunks[3]; -} int192m_T; - -typedef struct { - int192m_T re; - int192m_T im; -} cint192m_T; - -typedef struct { - uint64_T chunks[3]; -} uint192m_T; - -typedef struct { - uint192m_T re; - uint192m_T im; -} cuint192m_T; - -typedef struct { - uint64_T chunks[4]; -} int256m_T; - -typedef struct { - int256m_T re; - int256m_T im; -} cint256m_T; - -typedef struct { - uint64_T chunks[4]; -} uint256m_T; - -typedef struct { - uint256m_T re; - uint256m_T im; -} cuint256m_T; - -typedef struct { - uint64_T chunks[5]; -} int320m_T; - -typedef struct { - int320m_T re; - int320m_T im; -} cint320m_T; - -typedef struct { - uint64_T chunks[5]; -} uint320m_T; - -typedef struct { - uint320m_T re; - uint320m_T im; -} cuint320m_T; - -typedef struct { - uint64_T chunks[6]; -} int384m_T; - -typedef struct { - int384m_T re; - int384m_T im; -} cint384m_T; - -typedef struct { - uint64_T chunks[6]; -} uint384m_T; - -typedef struct { - uint384m_T re; - uint384m_T im; -} cuint384m_T; - -typedef struct { - uint64_T chunks[7]; -} int448m_T; - -typedef struct { - int448m_T re; - int448m_T im; -} cint448m_T; - -typedef struct { - uint64_T chunks[7]; -} uint448m_T; - -typedef struct { - uint448m_T re; - uint448m_T im; -} cuint448m_T; - -typedef struct { - uint64_T chunks[8]; -} int512m_T; - -typedef struct { - int512m_T re; - int512m_T im; -} cint512m_T; - -typedef struct { - uint64_T chunks[8]; -} uint512m_T; - -typedef struct { - uint512m_T re; - uint512m_T im; -} cuint512m_T; - -typedef struct { - uint64_T chunks[9]; -} int576m_T; - -typedef struct { - int576m_T re; - int576m_T im; -} cint576m_T; - -typedef struct { - uint64_T chunks[9]; -} uint576m_T; - -typedef struct { - uint576m_T re; - uint576m_T im; -} cuint576m_T; - -typedef struct { - uint64_T chunks[10]; -} int640m_T; - -typedef struct { - int640m_T re; - int640m_T im; -} cint640m_T; - -typedef struct { - uint64_T chunks[10]; -} uint640m_T; - -typedef struct { - uint640m_T re; - uint640m_T im; -} cuint640m_T; - -typedef struct { - uint64_T chunks[11]; -} int704m_T; - -typedef struct { - int704m_T re; - int704m_T im; -} cint704m_T; - -typedef struct { - uint64_T chunks[11]; -} uint704m_T; - -typedef struct { - uint704m_T re; - uint704m_T im; -} cuint704m_T; - -typedef struct { - uint64_T chunks[12]; -} int768m_T; - -typedef struct { - int768m_T re; - int768m_T im; -} cint768m_T; - -typedef struct { - uint64_T chunks[12]; -} uint768m_T; - -typedef struct { - uint768m_T re; - uint768m_T im; -} cuint768m_T; - -typedef struct { - uint64_T chunks[13]; -} int832m_T; - -typedef struct { - int832m_T re; - int832m_T im; -} cint832m_T; - -typedef struct { - uint64_T chunks[13]; -} uint832m_T; - -typedef struct { - uint832m_T re; - uint832m_T im; -} cuint832m_T; - -typedef struct { - uint64_T chunks[14]; -} int896m_T; - -typedef struct { - int896m_T re; - int896m_T im; -} cint896m_T; - -typedef struct { - uint64_T chunks[14]; -} uint896m_T; - -typedef struct { - uint896m_T re; - uint896m_T im; -} cuint896m_T; - -typedef struct { - uint64_T chunks[15]; -} int960m_T; - -typedef struct { - int960m_T re; - int960m_T im; -} cint960m_T; - -typedef struct { - uint64_T chunks[15]; -} uint960m_T; - -typedef struct { - uint960m_T re; - uint960m_T im; -} cuint960m_T; - -typedef struct { - uint64_T chunks[16]; -} int1024m_T; - -typedef struct { - int1024m_T re; - int1024m_T im; -} cint1024m_T; - -typedef struct { - uint64_T chunks[16]; -} uint1024m_T; - -typedef struct { - uint1024m_T re; - uint1024m_T im; -} cuint1024m_T; - -#endif /* MULTIWORD_TYPES_H */ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_add.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_add.obj deleted file mode 100644 index f5f03ffa8a6af6462a49899fefdac93f133d8185..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_add.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_bounds.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_bounds.obj deleted file mode 100644 index c7b3f5463670414575293d2c769d4e1474c5e6a2..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_bounds.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_constant.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_constant.obj deleted file mode 100644 index 3dc3173081aa9f4052c1a945720e3c515ddc9924..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_constant.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_mixer.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_mixer.obj deleted file mode 100644 index 678060b7ce7b9746acba61619839979818b4cce5..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_mixer.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_pid.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_pid.obj deleted file mode 100644 index eb1433a57819b04d777fe3bdf7bb53e50c2b53b7..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_pid.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypes.h b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypes.h deleted file mode 100644 index 4e712c27577ba17448ba1cd15dc4115f8a99252c..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypes.h +++ /dev/null @@ -1,59 +0,0 @@ -#ifndef RTWTYPES_H -#define RTWTYPES_H -#include "tmwtypes.h" -#include "simstruc_types.h" -#ifndef POINTER_T -# define POINTER_T - -typedef void * pointer_T; - -#endif - -/* Logical type definitions */ -#if (!defined(__cplusplus)) -# ifndef false -# define false (0U) -# endif - -# ifndef true -# define true (1U) -# endif -#endif - -#ifndef INT64_T -#define INT64_T - -typedef long long int64_T; - -#endif - -#ifndef UINT64_T -#define UINT64_T - -typedef unsigned long long uint64_T; - -#endif - -/*===========================================================================* - * Additional complex number type definitions * - *===========================================================================*/ -#ifndef CINT64_T -#define CINT64_T - -typedef struct { - int64_T re; - int64_T im; -} cint64_T; - -#endif - -#ifndef CUINT64_T -#define CUINT64_T - -typedef struct { - uint64_T re; - uint64_T im; -} cuint64_T; - -#endif -#endif /* RTWTYPES_H */ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypeschksum.mat b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypeschksum.mat deleted file mode 100644 index 33765b62acae356d99b321e989c3262231895b99..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypeschksum.mat and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.bat b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.bat deleted file mode 100644 index 718fd6ff8b46a8bcc8b84837bccb77e49059213d..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.bat +++ /dev/null @@ -1,15 +0,0 @@ -@echo off -set COMPILER=gcc - set COMPFLAGS=-c -fexceptions -fno-omit-frame-pointer -m64 -DMATLAB_MEX_FILE -DMATLAB_MEX_FILE - set OPTIMFLAGS=-O -DNDEBUG - set DEBUGFLAGS=-g - set LINKER=gcc - set LINKFLAGS=-m64 -Wl,--no-undefined -shared -L"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64" -llibmx -llibmex -llibmat -lm -llibmwlapack -llibmwblas -Wl,"C:\Program Files\MATLAB\R2016b/extern/lib/win64/mingw64/mexFunction.def" - set LINKDEBUGFLAGS=-g - set NAME_OUTPUT=-o "%OUTDIR%%MEX_NAME%%MEX_EXT%" -set PATH=C:\TDM-GCC-64\bin;C:\Program Files\MATLAB\R2016b\extern\include\win64;C:\Program Files\MATLAB\R2016b\extern\include;C:\Program Files\MATLAB\R2016b\simulink\include;C:\Program Files\MATLAB\R2016b\lib\win64;%MATLAB_BIN%;%PATH% -set INCLUDE=C:\TDM-GCC-64\include;;%INCLUDE% -set LIB=C:\TDM-GCC-64\lib;;%LIB% -set LIBPATH=C:\Program Files\MATLAB\R2016b\extern\lib\win64;%LIBPATH% - -gmake SHELL="cmd" -f test_model_sfun.gmk diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.c b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.c deleted file mode 100644 index 37a282f37607e1db89dfb37426d60aedea42b40f..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.c +++ /dev/null @@ -1,362 +0,0 @@ -/* Include files */ - -#define IN_SF_MACHINE_SOURCE 1 -#include "test_model_sfun.h" -#include "test_model_sfun_debug_macros.h" -#include "c15_test_model.h" - -/* Type Definitions */ - -/* Named Constants */ - -/* Variable Declarations */ - -/* Variable Definitions */ -uint32_T _test_modelMachineNumber_; - -/* Function Declarations */ - -/* Function Definitions */ -void test_model_initializer(void) -{ -} - -void test_model_terminator(void) -{ -} - -/* SFunction Glue Code */ -unsigned int sf_test_model_method_dispatcher(SimStruct *simstructPtr, unsigned - int chartFileNumber, const char* specsCksum, int_T method, void *data) -{ - if (chartFileNumber==15) { - c15_test_model_method_dispatcher(simstructPtr, method, data); - return 1; - } - - return 0; -} - -unsigned int sf_test_model_process_check_sum_call( int nlhs, mxArray * plhs[], - int nrhs, const mxArray * prhs[] ) -{ - -#ifdef MATLAB_MEX_FILE - - char commandName[20]; - if (nrhs<1 || !mxIsChar(prhs[0]) ) - return 0; - - /* Possible call to get the checksum */ - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"sf_get_check_sum")) - return 0; - plhs[0] = mxCreateDoubleMatrix( 1,4,mxREAL); - if (nrhs>1 && mxIsChar(prhs[1])) { - mxGetString(prhs[1], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (!strcmp(commandName,"machine")) { - ((real_T *)mxGetPr((plhs[0])))[0] = (real_T)(2933295744U); - ((real_T *)mxGetPr((plhs[0])))[1] = (real_T)(2244548132U); - ((real_T *)mxGetPr((plhs[0])))[2] = (real_T)(3790258605U); - ((real_T *)mxGetPr((plhs[0])))[3] = (real_T)(1409175729U); - } else if (nrhs==3 && !strcmp(commandName,"chart")) { - unsigned int chartFileNumber; - chartFileNumber = (unsigned int)mxGetScalar(prhs[2]); - switch (chartFileNumber) { - case 15: - { - extern void sf_c15_test_model_get_check_sum(mxArray *plhs[]); - sf_c15_test_model_get_check_sum(plhs); - break; - } - - default: - ((real_T *)mxGetPr((plhs[0])))[0] = (real_T)(0.0); - ((real_T *)mxGetPr((plhs[0])))[1] = (real_T)(0.0); - ((real_T *)mxGetPr((plhs[0])))[2] = (real_T)(0.0); - ((real_T *)mxGetPr((plhs[0])))[3] = (real_T)(0.0); - } - } else if (!strcmp(commandName,"target")) { - ((real_T *)mxGetPr((plhs[0])))[0] = (real_T)(1167153972U); - ((real_T *)mxGetPr((plhs[0])))[1] = (real_T)(91317778U); - ((real_T *)mxGetPr((plhs[0])))[2] = (real_T)(3880733235U); - ((real_T *)mxGetPr((plhs[0])))[3] = (real_T)(951854545U); - } else { - return 0; - } - } else { - ((real_T *)mxGetPr((plhs[0])))[0] = (real_T)(1563919274U); - ((real_T *)mxGetPr((plhs[0])))[1] = (real_T)(1658080807U); - ((real_T *)mxGetPr((plhs[0])))[2] = (real_T)(3992559932U); - ((real_T *)mxGetPr((plhs[0])))[3] = (real_T)(2585406222U); - } - - return 1; - -#else - - return 0; - -#endif - -} - -unsigned int sf_test_model_autoinheritance_info( int nlhs, mxArray * plhs[], int - nrhs, const mxArray * prhs[] ) -{ - -#ifdef MATLAB_MEX_FILE - - char commandName[32]; - char aiChksum[64]; - if (nrhs<3 || !mxIsChar(prhs[0]) ) - return 0; - - /* Possible call to get the autoinheritance_info */ - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_autoinheritance_info")) - return 0; - mxGetString(prhs[2], aiChksum,sizeof(aiChksum)/sizeof(char)); - aiChksum[(sizeof(aiChksum)/sizeof(char)-1)] = '\0'; - - { - unsigned int chartFileNumber; - chartFileNumber = (unsigned int)mxGetScalar(prhs[1]); - switch (chartFileNumber) { - case 15: - { - if (strcmp(aiChksum, "NhviQufdzoJMzgXQ3dS4TB") == 0) { - extern mxArray *sf_c15_test_model_get_autoinheritance_info(void); - plhs[0] = sf_c15_test_model_get_autoinheritance_info(); - break; - } - - plhs[0] = mxCreateDoubleMatrix(0,0,mxREAL); - break; - } - - default: - plhs[0] = mxCreateDoubleMatrix(0,0,mxREAL); - } - } - - return 1; - -#else - - return 0; - -#endif - -} - -unsigned int sf_test_model_get_eml_resolved_functions_info( int nlhs, mxArray * - plhs[], int nrhs, const mxArray * prhs[] ) -{ - -#ifdef MATLAB_MEX_FILE - - char commandName[64]; - if (nrhs<2 || !mxIsChar(prhs[0])) - return 0; - - /* Possible call to get the get_eml_resolved_functions_info */ - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_eml_resolved_functions_info")) - return 0; - - { - unsigned int chartFileNumber; - chartFileNumber = (unsigned int)mxGetScalar(prhs[1]); - switch (chartFileNumber) { - case 15: - { - extern const mxArray *sf_c15_test_model_get_eml_resolved_functions_info - (void); - mxArray *persistentMxArray = (mxArray *) - sf_c15_test_model_get_eml_resolved_functions_info(); - plhs[0] = mxDuplicateArray(persistentMxArray); - mxDestroyArray(persistentMxArray); - break; - } - - default: - plhs[0] = mxCreateDoubleMatrix(0,0,mxREAL); - } - } - - return 1; - -#else - - return 0; - -#endif - -} - -unsigned int sf_test_model_third_party_uses_info( int nlhs, mxArray * plhs[], - int nrhs, const mxArray * prhs[] ) -{ - char commandName[64]; - char tpChksum[64]; - if (nrhs<3 || !mxIsChar(prhs[0])) - return 0; - - /* Possible call to get the third_party_uses_info */ - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - mxGetString(prhs[2], tpChksum,sizeof(tpChksum)/sizeof(char)); - tpChksum[(sizeof(tpChksum)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_third_party_uses_info")) - return 0; - - { - unsigned int chartFileNumber; - chartFileNumber = (unsigned int)mxGetScalar(prhs[1]); - switch (chartFileNumber) { - case 15: - { - if (strcmp(tpChksum, "sL897IXghI8zmc3H8vRBKxD") == 0) { - extern mxArray *sf_c15_test_model_third_party_uses_info(void); - plhs[0] = sf_c15_test_model_third_party_uses_info(); - break; - } - } - - default: - plhs[0] = mxCreateDoubleMatrix(0,0,mxREAL); - } - } - - return 1; -} - -unsigned int sf_test_model_jit_fallback_info( int nlhs, mxArray * plhs[], int - nrhs, const mxArray * prhs[] ) -{ - char commandName[64]; - char tpChksum[64]; - if (nrhs<3 || !mxIsChar(prhs[0])) - return 0; - - /* Possible call to get the jit_fallback_info */ - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - mxGetString(prhs[2], tpChksum,sizeof(tpChksum)/sizeof(char)); - tpChksum[(sizeof(tpChksum)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_jit_fallback_info")) - return 0; - - { - unsigned int chartFileNumber; - chartFileNumber = (unsigned int)mxGetScalar(prhs[1]); - switch (chartFileNumber) { - case 15: - { - if (strcmp(tpChksum, "sL897IXghI8zmc3H8vRBKxD") == 0) { - extern mxArray *sf_c15_test_model_jit_fallback_info(void); - plhs[0] = sf_c15_test_model_jit_fallback_info(); - break; - } - } - - default: - plhs[0] = mxCreateDoubleMatrix(0,0,mxREAL); - } - } - - return 1; -} - -unsigned int sf_test_model_updateBuildInfo_args_info( int nlhs, mxArray * plhs[], - int nrhs, const mxArray * prhs[] ) -{ - char commandName[64]; - char tpChksum[64]; - if (nrhs<3 || !mxIsChar(prhs[0])) - return 0; - - /* Possible call to get the updateBuildInfo_args_info */ - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - mxGetString(prhs[2], tpChksum,sizeof(tpChksum)/sizeof(char)); - tpChksum[(sizeof(tpChksum)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_updateBuildInfo_args_info")) - return 0; - - { - unsigned int chartFileNumber; - chartFileNumber = (unsigned int)mxGetScalar(prhs[1]); - switch (chartFileNumber) { - case 15: - { - if (strcmp(tpChksum, "sL897IXghI8zmc3H8vRBKxD") == 0) { - extern mxArray *sf_c15_test_model_updateBuildInfo_args_info(void); - plhs[0] = sf_c15_test_model_updateBuildInfo_args_info(); - break; - } - } - - default: - plhs[0] = mxCreateDoubleMatrix(0,0,mxREAL); - } - } - - return 1; -} - -void test_model_debug_initialize(struct SfDebugInstanceStruct* debugInstance) -{ - _test_modelMachineNumber_ = sf_debug_initialize_machine(debugInstance, - "test_model","sfun",0,13,0,0,0); - sf_debug_set_machine_event_thresholds(debugInstance,_test_modelMachineNumber_, - 0,0); - sf_debug_set_machine_data_thresholds(debugInstance,_test_modelMachineNumber_,0); -} - -void test_model_register_exported_symbols(SimStruct* S) -{ -} - -static mxArray* sRtwOptimizationInfoStruct= NULL; -typedef struct SfOptimizationInfoFlagsTag { - boolean_T isRtwGen; - boolean_T isModelRef; - boolean_T isExternal; -} SfOptimizationInfoFlags; - -static SfOptimizationInfoFlags sOptimizationInfoFlags; -void unload_test_model_optimization_info(void); -mxArray* load_test_model_optimization_info(boolean_T isRtwGen, boolean_T - isModelRef, boolean_T isExternal) -{ - if (sOptimizationInfoFlags.isRtwGen != isRtwGen || - sOptimizationInfoFlags.isModelRef != isModelRef || - sOptimizationInfoFlags.isExternal != isExternal) { - unload_test_model_optimization_info(); - } - - sOptimizationInfoFlags.isRtwGen = isRtwGen; - sOptimizationInfoFlags.isModelRef = isModelRef; - sOptimizationInfoFlags.isExternal = isExternal; - if (sRtwOptimizationInfoStruct==NULL) { - sRtwOptimizationInfoStruct = sf_load_rtw_optimization_info("test_model", - "test_model"); - mexMakeArrayPersistent(sRtwOptimizationInfoStruct); - } - - return(sRtwOptimizationInfoStruct); -} - -void unload_test_model_optimization_info(void) -{ - if (sRtwOptimizationInfoStruct!=NULL) { - mxDestroyArray(sRtwOptimizationInfoStruct); - sRtwOptimizationInfoStruct = NULL; - } -} diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.gmk b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.gmk deleted file mode 100644 index 7f268eea6059e204d90d40a123b04e0c33a4b704..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.gmk +++ /dev/null @@ -1,95 +0,0 @@ -#--------------------------- Tool Specifications ------------------------- -# -# Modify the following macros to reflect the tools you wish to use for -# compiling and linking your code. -# -CC = "C:\Program Files\MATLAB\R2016b\bin\win64\mex.exe" -LD = $(CC) - -MODEL = test_model -TARGET = sfun -MODULE_SRCS = c15_test_model.c -MODEL_SRC = test_model_sfun.c -MODEL_REG = test_model_sfun_registry.c -MAKEFILE = test_model_sfun.gmk -MATLAB_ROOT = c:\program files\matlab\r2016b\toolbox\stateflow\stateflow\..\..\.. -BUILDARGS = -#------------------------------ Include/Lib Path ------------------------------ - -USER_INCLUDES = -I"C:\Users\Andy\documents\School\microcart\GitRepo\microcart_17-18\controls\model\logginganalysis\slprj\_sfprj\test_model\_self\sfun\src" -I"C:\Users\Andy\documents\School\microcart\GitRepo\microcart_17-18\controls\model\logginganalysis" -I"C:\Users\Andy\documents\School\microcart\GitRepo\microcart_17-18\controls\model\quad_files" -I"C:\Users\Andy\documents\School\microcart\GitRepo\microcart_17-18\controls\model" -I"C:\Users\Andy\documents\School\microcart\GitRepo\microcart_17-18\controls\model\quad_files\graph_blocks" -AUX_INCLUDES = -MLSLSF_INCLUDES = \ - -I"C:\Program Files\MATLAB\R2016b\extern\include" \ - -I"C:\Program Files\MATLAB\R2016b\simulink\include" \ - -I"C:\Program Files\MATLAB\R2016b\simulink\include\sf_runtime" \ - -I"C:\Program Files\MATLAB\R2016b\stateflow\c\mex\include" \ - -I"C:\Program Files\MATLAB\R2016b\rtw\c\src" \ - -I"C:\Users\Andy\Documents\School\MicroCART\GitRepo\MicroCART_17-18\controls\model\loggingAnalysis\slprj\_sfprj\test_model\_self\sfun\src" - -THIRD_PARTY_INCLUDES = - -INCLUDE_PATH = $(USER_INCLUDES) $(AUX_INCLUDES) $(MLSLSF_INCLUDES) $(COMPILER_INCLUDES) $(THIRD_PARTY_INCLUDES) - -#----------------- Compiler and Linker Options -------------------------------- - -# Optimization Options - -CC_OPTS = -CPP_REQ_DEFINES = -DMATLAB_MEX_FILE - -# Uncomment this line to move warning level to W4 -# cflags = $(cflags:W3=W4) -CFLAGS = $(CC_OPTS) $(CPP_REQ_DEFINES) $(INCLUDE_PATH) - -LDFLAGS = - -AUXLDFLAGS = -#----------------------------- Source Files ----------------------------------- - -THIRD_PARTY_SRCS = -REQ_SRCS = $(MODEL_SRC) $(MODEL_REG) $(MODULE_SRCS) $(THIRD_PARTY_SRCS) - -USER_ABS_OBJS = \ - c_controller.obj \ - node_constant.obj \ - node_pid.obj \ - node_mixer.obj \ - node_bounds.obj \ - node_add.obj \ - -AUX_ABS_OBJS = - -REQ_OBJS = $(REQ_SRCS:.cpp=.obj) -REQ_OBJS2 = $(REQ_OBJS:.c=.obj) -OBJS = $(REQ_OBJS2) $(USER_ABS_OBJS) $(AUX_ABS_OBJS) $(THIRD_PARTY_OBJS) -OBJLIST_FILE = test_model_sfun.mol -SFCLIB = -AUX_LNK_OBJS = -USER_LIBS = -PARLIB = - -#--------------------------------- Rules -------------------------------------- - -MEX_FILE_NAME = $(MODEL)_$(TARGET).mexw64 - - $(MEX_FILE_NAME): $(MAKEFILE) $(OBJS) $(SFCLIB) $(AUX_LNK_OBJS) - @echo ### Linking ... - $(LD) -silent LDFLAGS="$$LDFLAGS $(LDFLAGS) $(AUXLDFLAGS)" -output $(MEX_FILE_NAME) @$(OBJLIST_FILE) $(USER_LIBS) $(SFCLIB) $(PARLIB) $(IPPLIB) $(THIRD_PARTY_LIBS) -%.obj : %.c - $(CC) -c $(CFLAGS) $< - -%.obj : %.cpp - $(CC) -c $(CFLAGS) $< - -c_controller.obj : C:/Users/Andy/DOCUME~1/School/MICROC~1/GitRepo/MICROC~1/controls/model/c_controller.c - $(CC) -c $(CFLAGS) $< -node_constant.obj : C:/Users/Andy/DOCUME~1/School/MICROC~1/GitRepo/MICROC~1/controls/model/QUAD_F~1/GRAPH_~1/node_constant.c - $(CC) -c $(CFLAGS) $< -node_pid.obj : C:/Users/Andy/DOCUME~1/School/MICROC~1/GitRepo/MICROC~1/controls/model/QUAD_F~1/GRAPH_~1/node_pid.c - $(CC) -c $(CFLAGS) $< -node_mixer.obj : C:/Users/Andy/DOCUME~1/School/MICROC~1/GitRepo/MICROC~1/controls/model/QUAD_F~1/GRAPH_~1/node_mixer.c - $(CC) -c $(CFLAGS) $< -node_bounds.obj : C:/Users/Andy/DOCUME~1/School/MICROC~1/GitRepo/MICROC~1/controls/model/QUAD_F~1/GRAPH_~1/node_bounds.c - $(CC) -c $(CFLAGS) $< -node_add.obj : C:/Users/Andy/DOCUME~1/School/MICROC~1/GitRepo/MICROC~1/controls/model/QUAD_F~1/GRAPH_~1/node_add.c - $(CC) -c $(CFLAGS) $< diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.h b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.h deleted file mode 100644 index 5670253ff6dbe2f5639778848c54beb6faea9f40..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.h +++ /dev/null @@ -1,52 +0,0 @@ -#ifndef __test_model_sfun_h__ -#define __test_model_sfun_h__ - -/* Include files */ -#define S_FUNCTION_NAME sf_sfun -#include "sf_runtime/sfc_sf.h" -#include "sf_runtime/sfc_mex.h" -#include "sf_runtime/sf_runtime_errors.h" -#include "rtwtypes.h" -#include "simtarget/slSimTgtClientServerAPIBridge.h" -#include "sf_runtime/sfc_sdi.h" -#include "sf_runtime/sf_test_language.h" -#include "multiword_types.h" -#include "sf_runtime/sfc_messages.h" -#include "sf_runtime/sfcdebug.h" -#define rtInf (mxGetInf()) -#define rtMinusInf (-(mxGetInf())) -#define rtNaN (mxGetNaN()) -#define rtIsNaN(X) ((int)mxIsNaN(X)) -#define rtIsInf(X) ((int)mxIsInf(X)) - -struct SfDebugInstanceStruct; -extern struct SfDebugInstanceStruct* sfGlobalDebugInstanceStruct; - -/* Custom Code from Simulation Target dialog*/ -#include "c_controller.h" - -/* Type Definitions */ - -/* Named Constants */ - -/* Variable Declarations */ -extern uint32_T _test_modelMachineNumber_; - -/* Variable Definitions */ - -/* Function Declarations */ -extern void test_model_initializer(void); -extern void test_model_terminator(void); - -/* Function Definitions */ - -/* We load infoStruct for rtw_optimation_info on demand in mdlSetWorkWidths and - free it immediately in mdlStart. Given that this is machine-wide as - opposed to chart specific, we use NULL check to make sure it gets loaded - and unloaded once per machine even though the methods mdlSetWorkWidths/mdlStart - are chart/instance specific. The following methods abstract this out. */ -extern mxArray* load_test_model_optimization_info(boolean_T isRtwGen, boolean_T - isModelRef, boolean_T isExternal); -extern void unload_test_model_optimization_info(void); - -#endif diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.mol b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.mol deleted file mode 100644 index 6b339f36e8cbb1fa23b17f189510649958aae54d..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.mol +++ /dev/null @@ -1,27 +0,0 @@ -test_model_sfun.obj -c15_test_model.obj -test_model_sfun_registry.obj -c_controller.obj -node_constant.obj -node_pid.obj -node_mixer.obj -node_bounds.obj -node_add.obj - - - -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\sf_runtime.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmx.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmex.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmat.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libfixedpoint.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libut.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmwmathutil.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libemlrt.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmwsl_log_load_blocks.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmwsimulink.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmwsl_sfcn_cov_bridge.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmwsl_simtarget_core.lib" -"C:\Program Files\MATLAB\R2016b\extern\lib\win64\mingw64\libmwsl_simtarget_instrumentation.lib" -"-LC:\Program Files\MATLAB\R2016b\bin\win64" "-llibmwipp" - diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.obj deleted file mode 100644 index d4ddc8caec577ec8bf447b339d33b34f6bd23462..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.obj and /dev/null differ diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_debug_macros.h b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_debug_macros.h deleted file mode 100644 index bd991d4b8d54f27595a03c0df12ea4fe92e13cc8..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_debug_macros.h +++ /dev/null @@ -1,466 +0,0 @@ - #ifndef __SF_DEBUG_MACROS_H__ - #define __SF_DEBUG_MACROS_H__ - extern unsigned int _test_modelMachineNumber_; - #define _SFD_SET_DATA_VALUE_PTR(v1,v2)\ - sf_debug_set_instance_data_value_ptr(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,CHARTINSTANCE_INSTANCENUMBER,v1,(void *)(v2),NULL); - #define _SFD_UNSET_DATA_VALUE_PTR(v1)\ - sf_debug_unset_instance_data_value_ptr(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,CHARTINSTANCE_INSTANCENUMBER,v1); - #define _SFD_SET_DATA_VALUE_PTR_VAR_DIM(v1,v2,v3)\ - sf_debug_set_instance_data_value_ptr(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,CHARTINSTANCE_INSTANCENUMBER,v1,(void *)(v2),(void *)(v3)); - #define _SFD_DATA_RANGE_CHECK_MIN_MAX(dVal,dNum,objectTypeEnum,objectNumber,activeEventNumber,isFasterRuntimeOn,dMin,dMax,ssid,offset,length)\ - sf_debug_data_range_error_wrapper_min_max(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - dNum,(double)(dVal),\ - (unsigned int)objectTypeEnum,(unsigned int)objectNumber,(int)activeEventNumber,_sfTime_,(bool)isFasterRuntimeOn,(double)dMin,(double)dMax,ssid,offset,length) - #define _SFD_DATA_RANGE_CHECK_MIN(dVal,dNum,objectTypeEnum,objectNumber,activeEventNumber,isFasterRuntimeOn,dMin,ssid,offset,length)\ - sf_debug_data_range_error_wrapper_min(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - dNum,(double)(dVal),\ - (unsigned int)objectTypeEnum,(unsigned int)objectNumber,(int)activeEventNumber,_sfTime_,(bool)isFasterRuntimeOn,(double)dMin,ssid,offset,length) - #define _SFD_DATA_RANGE_CHECK_MAX(dVal,dNum,objectTypeEnum,objectNumber,activeEventNumber,isFasterRuntimeOn,dMax,ssid,offset,length)\ - sf_debug_data_range_error_wrapper_max(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - dNum,(double)(dVal),\ - (unsigned int)objectTypeEnum,(unsigned int)objectNumber,(int)activeEventNumber,_sfTime_,(bool)isFasterRuntimeOn,(double)dMax,ssid,offset,length) - #define _SFD_DATA_RANGE_CHECK(dVal,dNum,objectTypeEnum,objectNumber,activeEventNumber,isFasterRuntimeOn)\ - sf_debug_data_range_wrapper(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - dNum,(double)(dVal),\ - (unsigned int)objectTypeEnum,(unsigned int)objectNumber,(int)activeEventNumber,_sfTime_,(bool)isFasterRuntimeOn) - #define _SFD_DATA_READ_BEFORE_WRITE_ERROR(dNum,objectTypeEnum,objectNumber,activeEventNumber,isFasterRuntimeOn)\ - sf_debug_read_before_write_error(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (unsigned int)(dNum),\ - (unsigned int)objectTypeEnum,(unsigned int)objectNumber,(int)activeEventNumber,_sfTime_,(bool)isFasterRuntimeOn) - #define _SFD_ARRAY_BOUNDS_CHECK(v1,v2,v3,v4,v5,v6) \ - sf_debug_data_array_bounds_error_check(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(int)(v2),(int)(v3),(int)(v4),(int)(v5),(int)(v6)) - #define _SFD_RUNTIME_SIZE_MISMATCH_CHECK(v1,v2,v3,v4,v5) \ - sf_debug_data_runtime_size_mismatch_error_check(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(unsigned int)(v3),(int)(v4),(int)(v5)) - #define _SFD_EML_ARRAY_BOUNDS_CHECK(v1,v2,v3,v4,v5,v6) \ - sf_debug_eml_data_array_bounds_error_check(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(int)(v2),(int)(v3),(int)(v4),(int)(v5),(int)(v6)) - #ifdef INT_TYPE_64_IS_SUPPORTED - #define _SFD_EML_ARRAY_BOUNDS_CHECK_INT64(v1,v2,v3,v4,v5,v6) \ - sf_debug_eml_data_array_bounds_error_check_int64(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(int64_T)(v2),(int)(v3),(int)(v4),(int)(v5),(int)(v6)) - #endif - #define _SFD_INTEGER_CHECK(v1,v2) \ - sf_debug_integer_check(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(double)(v2)) - #define _SFD_NOT_NAN_CHECK(v1,v2) \ - sf_debug_not_nan_check(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(double)(v2)) - #define _SFD_NON_NEGATIVE_CHECK(v1,v2) \ - sf_debug_non_negative_check(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(double)(v2)) - #define _SFD_CAST_TO_UINT8(v1) \ - sf_debug_cast_to_uint8_T(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),0,0) - #define _SFD_CAST_TO_UINT16(v1) \ - sf_debug_cast_to_uint16_T(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),0,0) - #define _SFD_CAST_TO_UINT32(v1) \ - sf_debug_cast_to_uint32_T(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),0,0) - #define _SFD_CAST_TO_INT8(v1) \ - sf_debug_cast_to_int8_T(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),0,0) - #define _SFD_CAST_TO_INT16(v1) \ - sf_debug_cast_to_int16_T(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),0,0) - #define _SFD_CAST_TO_INT32(v1) \ - sf_debug_cast_to_int32_T(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),0,0) - #define _SFD_CAST_TO_SINGLE(v1) \ - sf_debug_cast_to_real32_T(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),0,0) - #define _SFD_ANIMATE() sf_debug_animate(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER) - #define _SFD_CHART_CALL(v1,v2,v3,v4) sf_debug_call(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - CHART_OBJECT,v1,v2,v3,v4,\ - 0,NULL,_sfTime_,1) - #define _SFD_MESSAGE_POST_CALL(v1) sf_debug_register_message_post_receive_info(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - v1,_sfTime_,1) - #define _SFD_MESSAGE_RECEIVE_CALL(v1) sf_debug_register_message_post_receive_info(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - v1,_sfTime_,0) - #define _SFD_CC_CALL(v2,v3,v4) _SFD_CHART_CALL(CHART_OBJECT,v2,v3,v4) - #define _SFD_CS_CALL(v2,v3,v4) _SFD_CHART_CALL(STATE_OBJECT,v2,v3,v4) - #define _SFD_CT_CALL(v2,v3,v4) _SFD_CHART_CALL(TRANSITION_OBJECT,v2,v3,v4) - #define _SFD_CE_CALL(v2,v3,v4) _SFD_CHART_CALL(EVENT_OBJECT,v2,v3,v4) - #define _SFD_CM_CALL(v2,v3,v4) _SFD_CHART_CALL(MESSAGE_OBJECT,v2,v3,v4) - #define _SFD_EML_CALL(v1,v2,v3) eml_debug_line_call(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - v1,v2,\ - v3,_sfTime_,0) - #define _SFD_SCRIPT_TRANSLATION(v1,v2,v3,v4) sf_debug_set_script_translation(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - v1,v2,v3,v4) - #define _SFD_SCRIPT_CALL(v1,v2,v3) eml_debug_line_call(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - v1,v2,\ - v3,_sfTime_,1) - #define _SFD_CCP_CALL(v3,v4,v5,v6) sf_debug_call(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - CHART_OBJECT,TRANSITION_OBJECT,TRANSITION_GUARD_COVERAGE_TAG,v3,v6,\ - v4,NULL,_sfTime_,(unsigned int)(v5)) - #define _SFD_STATE_TEMPORAL_THRESHOLD(v1,v2,v4) sf_debug_temporal_threshold(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (unsigned int)(v1),(v2),STATE_OBJECT,(v4)) - #define _SFD_TRANS_TEMPORAL_THRESHOLD(v1,v2,v4) sf_debug_temporal_threshold(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (unsigned int)(v1),(v2),TRANSITION_OBJECT,(v4)) - #define CV_EVAL(v1,v2,v3,v4) cv_eval_point(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4)) - #define CV_CHART_EVAL(v2,v3,v4) CV_EVAL(CHART_OBJECT,(v2),(v3),(v4)) - #define CV_STATE_EVAL(v2,v3,v4) CV_EVAL(STATE_OBJECT,(v2),(v3),(v4)) - #define CV_TRANSITION_EVAL(v1,v2) cv_eval_point(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - TRANSITION_OBJECT,(v1),0,((v2)!=0)) - #define CV_RELATIONAL_EVAL(v1,v2,v3,v4,v5,v6,v7,v8) cv_eval_relational(sfGlobalDebugInstanceStruct,_test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8)) - #define CV_BASIC_BLOCK_EVAL(v1,v2,v3) cv_eval_basic_block(sfGlobalDebugInstanceStruct,_test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3)) - #define CV_SATURATION_EVAL(v1,v2,v3,v4,v5) cv_eval_saturation(sfGlobalDebugInstanceStruct,_test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5)) - #define CV_SATURATION_ACCUM(v1,v2,v3,v4) cv_saturation_accum(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4)) - #define CV_TESTOBJECTIVE_EVAL(v1,v2,v3,v4) cv_eval_testobjective(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4)) - - /* Coverage Macros for MATLAB */ - #define CV_EML_EVAL(v1,v2,v3,v4,v5) cv_eml_eval(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(int)(v5)) - #define CV_EML_FCN(v2,v3) CV_EML_EVAL(CV_EML_FCN_CHECK,(v2),1,(v3),0) - #define CV_EML_TESTOBJECTIVE(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_TESTOBJECTIVE_CHECK,(v2),(v3),(v4),((v5) != 0)) - #define CV_EML_SATURATION(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_SATURATION_CHECK,(v2),(v3),(v4),((v5) != 0)) - #define CV_EML_SATURATION_ACCUM(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_SATURATION_ACCUM_CHECK,(v2),(v3),(v4),(v5)) - #define CV_EML_IF(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_IF_CHECK,(v2),(v3),(v4),((v5) != 0)) - #define CV_EML_FOR(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_FOR_CHECK,(v2),(v3),(v4),(v5)) - #define CV_EML_WHILE(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_WHILE_CHECK,(v2),(v3),(v4),((v5) != 0)) - #define CV_EML_SWITCH(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_SWITCH_CHECK,(v2),(v3),(v4),(v5)) - #define CV_EML_COND(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_COND_CHECK,(v2),(v3),(v4),((v5) != 0)) - #define CV_EML_MCDC(v2,v3,v4,v5) CV_EML_EVAL(CV_EML_MCDC_CHECK,(v2),(v3),(v4),(v5)) - #define CV_SCRIPT_EVAL(v1,v2,v3,v4) cv_script_eval(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(int)(v4)) - #define CV_SCRIPT_FCN(v2,v3) CV_SCRIPT_EVAL(CV_SCRIPT_FCN_CHECK,(v2),(v3),0) - #define CV_SCRIPT_TESTOBJECTIVE(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_TESTOBJECTIVE_CHECK,(v2),(v3),((v4) != 0)) - #define CV_SCRIPT_SATURATION(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_SATURATION_CHECK,(v2),(v3),((v4) != 0)) - #define CV_SCRIPT_SATURATION_ACCUM(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_SATURATION_ACCUM_CHECK,(v2),(v3),(v4)) - #define CV_SCRIPT_IF(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_IF_CHECK,(v2),(v3),((v4) != 0)) - #define CV_SCRIPT_FOR(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_FOR_CHECK,(v2),(v3),(v4)) - #define CV_SCRIPT_WHILE(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_WHILE_CHECK,(v2),(v3),((v4) != 0)) - #define CV_SCRIPT_SWITCH(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_SWITCH_CHECK,(v2),(v3),(v4)) - #define CV_SCRIPT_COND(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_COND_CHECK,(v2),(v3),((v4) != 0)) - #define CV_SCRIPT_MCDC(v2,v3,v4) CV_SCRIPT_EVAL(CV_SCRIPT_MCDC_CHECK,(v2),(v3),(v4)) - - #define _SFD_CV_INIT_EML(v1,v2,v3,v4,v5,v6,v7,v8,v9,v10,v11,v12) cv_eml_init_script(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8),(v9),(v10),(v11),(v12)) - - #define _SFD_CV_INIT_EML_FCN(v1,v2,v3,v4,v5,v6) cv_eml_init_fcn(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_EML_BASIC_BLOCK(v1,v2,v3,v4,v5) cv_eml_init_basic_block(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5)) - - #define _SFD_CV_INIT_EML_TESTOBJECTIVE(v1,v2,v3,v4,v5,v6,v7) cv_eml_init_testobjective(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7)) - - #define _SFD_CV_INIT_EML_SATURATION(v1,v2,v3,v4,v5,v6) cv_eml_init_saturation(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_EML_IF(v1,v2,v3,v4,v5,v6,v7) cv_eml_init_if(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7)) - - #define _SFD_CV_INIT_EML_FOR(v1,v2,v3,v4,v5,v6) cv_eml_init_for(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_EML_WHILE(v1,v2,v3,v4,v5,v6) cv_eml_init_while(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_EML_MCDC(v1,v2,v3,v4,v5,v6,v7,v8,v9,v10,v11) cv_eml_init_mcdc(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8),(v9),(v10),(v11)) - - #define _SFD_CV_INIT_EML_RELATIONAL(v1,v2,v3,v4,v5,v6,v7) cv_eml_init_relational(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7)) - - #define _SFD_CV_INIT_EML_SWITCH(v1,v2,v3,v4,v5,v6,v7,v8,v9) cv_eml_init_switch(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8),(v9)) - - #define _SFD_CV_INIT_SCRIPT(v1,v2,v3,v4,v5,v6,v7,v8,v9,v10,v11) cv_script_init_script(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8),(v9),(v10),(v11)) - - #define _SFD_CV_INIT_SCRIPT_FCN(v1,v2,v3,v4,v5,v6) cv_script_init_fcn(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_SCRIPT_BASIC_BLOCK(v1,v2,v3,v4,v5) cv_script_init_basic_block(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5)) - - #define _SFD_CV_INIT_SCRIPT_TESTOBJECTIVE(v1,v2,v3,v4,v5,v6) cv_script_init_testobjective(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_SCRIPT_SATURATION(v1,v2,v3,v4,v5) cv_script_init_saturation(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5)) - - #define _SFD_CV_INIT_SCRIPT_IF(v1,v2,v3,v4,v5,v6) cv_script_init_if(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_SCRIPT_FOR(v1,v2,v3,v4,v5) cv_script_init_for(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5)) - - #define _SFD_CV_INIT_SCRIPT_WHILE(v1,v2,v3,v4,v5) cv_script_init_while(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5)) - - #define _SFD_CV_INIT_SCRIPT_MCDC(v1,v2,v3,v4,v5,v6,v7,v8,v9,v10) cv_script_init_mcdc(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8),(v9),(v10)) - - #define _SFD_CV_INIT_SCRIPT_RELATIONAL(v1,v2,v3,v4,v5,v6) cv_script_init_relational(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_SCRIPT_SWITCH(v1,v2,v3,v4,v5,v6,v7,v8) cv_script_init_switch(sfGlobalDebugInstanceStruct, \ - _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8)) - - - #define _SFD_SET_DATA_PROPS(dataNumber,dataScope,isInputData,isOutputData,dataName)\ - sf_debug_set_chart_data_props(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,\ - (dataNumber),(dataScope),(isInputData),(isOutputData),(dataName)) - #define _SFD_SET_DATA_COMPILED_PROPS(dataNumber,dataType,numDims,dimArray,isFixedPoint,isSigned,wordLength,bias,slope,exponent,complexity,mexOutFcn, mexInFcn)\ - sf_debug_set_chart_data_compiled_props(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,CHARTINSTANCE_INSTANCENUMBER,\ - (dataNumber),(dataType),(numDims),(dimArray),(isFixedPoint),(isSigned),(wordLength),(bias),(slope),(exponent),(complexity),(mexOutFcn),(mexInFcn)) - #define _SFD_STATE_INFO(v1,v2,v3)\ - sf_debug_set_chart_state_info(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,(v1),(v2),(v3)) - #define _SFD_CH_SUBSTATE_INDEX(v1,v2)\ - sf_debug_set_chart_substate_index(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,(v1),(v2)) - #define _SFD_ST_SUBSTATE_INDEX(v1,v2,v3)\ - sf_debug_set_chart_state_substate_index(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,(v1),(v2),(v3)) - #define _SFD_ST_SUBSTATE_COUNT(v1,v2)\ - sf_debug_set_chart_state_substate_count(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,(v1),(v2)) - #define _SFD_DATA_CHANGE_EVENT_COUNT(v1,v2) \ - sf_debug_set_number_of_data_with_change_event_for_chart(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,\ - (v1),(v2)) - #define _SFD_STATE_ENTRY_EVENT_COUNT(v1,v2) \ - sf_debug_set_number_of_states_with_entry_event_for_chart(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,\ - (v1),(v2)) - #define _SFD_STATE_EXIT_EVENT_COUNT(v1,v2) \ - sf_debug_set_number_of_states_with_exit_event_for_chart(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,\ - (v1),(v2)) - #define _SFD_EVENT_SCOPE(v1,v2)\ - sf_debug_set_chart_event_scope(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,(v1),(v2)) - - #define _SFD_CH_SUBSTATE_COUNT(v1) \ - sf_debug_set_chart_substate_count(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,(v1)) - #define _SFD_CH_SUBSTATE_DECOMP(v1) \ - sf_debug_set_chart_decomposition(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,(v1)) - - #define _SFD_CV_INIT_CHART(v1,v2,v3,v4)\ - sf_debug_cv_init_chart(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,(v1),(v2),(v3),(v4)) - - #define _SFD_CV_INIT_STATE(v1,v2,v3,v4,v5,v6,v7,v8)\ - sf_debug_cv_init_state(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,(v1),(v2),(v3),(v4),(v5),(v6),(v7),(v8)) - - #define _SFD_CV_INIT_TRANSITION_SATURATION(v1,v2,v3,v4)\ - sf_debug_cv_init_saturation(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - TRANSITION_OBJECT,(v1),(v2),(v3),(v4)) - - #define _SFD_CV_INIT_TRANSITION_RELATIONALOP(v1,v2,v3,v4,v5,v6)\ - sf_debug_cv_init_relationalop(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - TRANSITION_OBJECT,(v1),(v2),(v3),(v4),(v5),(v6)) - - #define _SFD_CV_INIT_STATE_SATURATION(v1,v2,v3,v4)\ - sf_debug_cv_init_saturation(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - STATE_OBJECT, (v1),(v2),(v3),(v4)) - - #define _SFD_CV_INIT_TRANSITION_TESTOBJECTIVE(v1,v2,v3,v4)\ - sf_debug_cv_init_testobjectives(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - TRANSITION_OBJECT,(v1),(v2),(v3),(v4)) - - #define _SFD_CV_INIT_STATE_TESTOBJECTIVE(v1,v2,v3,v4)\ - sf_debug_cv_init_testobjectives(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - STATE_OBJECT, (v1),(v2),(v3),(v4)) - - #define _SFD_CV_INIT_TRANS(v1,v2,v3,v4,v5,v6)\ - sf_debug_cv_init_trans(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (v1),(v2),(v3),(v4),(v5),(v6)) - #endif - - #define _SFD_SET_MACHINE_DATA_VALUE_PTR(v0,v1,v2) sf_debug_set_machine_data_value_ptr(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_STORE_CURRENT_STATE_CONFIGURATION(v0,v1,v2) sf_debug_store_current_state_configuration(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_RESTORE_PREVIOUS_STATE_CONFIGURATION(v0,v1,v2) sf_debug_restore_previous_state_configuration(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_RESTORE_PREVIOUS_STATE_CONFIGURATION2(v0,v1,v2) sf_debug_restore_previous_state_configuration2(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_SYMBOL_SCOPE_PUSH(v0,v1) sf_debug_symbol_scope_push(sfGlobalDebugInstanceStruct,v0,v1) - #define _SFD_SYMBOL_SCOPE_PUSH_EML(v0,v1,v2,v3,v4) sf_debug_symbol_scope_push_eml(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4) - #define _SFD_SYMBOL_SCOPE_POP() sf_debug_symbol_scope_pop(sfGlobalDebugInstanceStruct) - #define _SFD_SYMBOL_SCOPE_ADD(v0,v1,v2) sf_debug_symbol_scope_add(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_SYMBOL_SCOPE_ADD_IMPORTABLE(v0,v1,v2,v3) sf_debug_symbol_scope_add_importable(sfGlobalDebugInstanceStruct,v0,v1,v2,v3) - #define _SFD_SYMBOL_SCOPE_ADD_EML(v0,v1,v2) sf_debug_symbol_scope_add_eml(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_SYMBOL_SCOPE_ADD_EML_IMPORTABLE(v0,v1,v2,v3) sf_debug_symbol_scope_add_eml_importable(sfGlobalDebugInstanceStruct,v0,v1,v2,v3) - #define _SFD_SYMBOL_SCOPE_ADD_DYN(v0,v1,v2,v3,v4,v5) sf_debug_symbol_scope_add_dyn(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4,v5) - #define _SFD_SYMBOL_SCOPE_ADD_DYN_IMPORTABLE(v0,v1,v2,v3,v4,v5,v6) sf_debug_symbol_scope_add_dyn_importable(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4,v5,v6) - #define _SFD_SYMBOL_SCOPE_ADD_EML_DYN(v0,v1,v2,v3,v4,v5) sf_debug_symbol_scope_add_eml_dyn(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4,v5) - #define _SFD_SYMBOL_SCOPE_ADD_EML_DYN_IMPORTABLE(v0,v1,v2,v3,v4,v5,v6) sf_debug_symbol_scope_add_eml_dyn_importable(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4,v5,v6) - #define _SFD_SYMBOL_SCOPE_ADD_EML_DYN_EMX(v0,v1,v2,v3,v4,v5,v6,v7) sf_debug_symbol_scope_add_eml_dyn_emx(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4,v5,v6,v7) - #define _SFD_SYMBOL_SCOPE_ADD_EML_DYN_EMX_IMPORTABLE(v0,v1,v2,v3,v4,v5,v6,v7,v8) sf_debug_symbol_scope_add_eml_dyn_emx_importable(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4,v5,v6,v7,v8) - #define _SFD_SYMBOL_SCOPE_ADD_VERBOSE(v0,v1,v2,v3,v4,v5,v6,v7,v8,v9,v10,v11,v12,v13,v14) sf_debug_symbol_scope_add_verbose(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4,v5,v6,v7,v8,v9,v10,v11,v12,v13,v14) - #define _SFD_SYMBOL_SWITCH(v0,v1) sf_debug_symbol_switch(sfGlobalDebugInstanceStruct,v0,v1) - #define _SFD_CHECK_FOR_STATE_INCONSISTENCY(v0,v1,v2) sf_debug_check_for_state_inconsistency(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_REPORT_STATE_INCONSISTENCY_ERROR(objectTypeEnum,objectNumber,activeEventNumber,isFasterRuntimeOn) \ - sf_debug_report_state_inconsistency_error(sfGlobalDebugInstanceStruct, _test_modelMachineNumber_,\ - CHARTINSTANCE_CHARTNUMBER,\ - CHARTINSTANCE_INSTANCENUMBER,\ - (unsigned int)objectTypeEnum,(unsigned int)objectNumber,(int)activeEventNumber,_sfTime_,(bool)isFasterRuntimeOn) - #define _SFD_SET_HONOR_BREAKPOINTS(v0) sf_debug_set_honor_breakpoints(sfGlobalDebugInstanceStruct, v0) - #define _SFD_GET_ANIMATION() sf_debug_get_animation(sfGlobalDebugInstanceStruct) - #define _SFD_SET_ANIMATION(v0) sf_debug_set_animation(sfGlobalDebugInstanceStruct,v0) - #define _SFD_SIZE_EQ_CHECK_1D(v0,v1) sf_debug_size_eq_check_1d(sfGlobalDebugInstanceStruct,v0,v1) - #define _SFD_SIZE_EQ_CHECK_ND(v0,v1,v2) sf_debug_size_eq_check_nd(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_DIM_SIZE_EQ_CHECK(v0,v1,v2) sf_debug_dim_size_eq_check(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_DIM_SIZE_GEQ_CHECK(v0,v1,v2) sf_debug_dim_size_geq_check(sfGlobalDebugInstanceStruct,v0,v1,v2) - #define _SFD_SUB_ASSIGN_SIZE_CHECK_ND(v0,v1,v2,v3) sf_debug_sub_assign_size_check_nd(sfGlobalDebugInstanceStruct,v0,v1,v2,v3) - #define _SFD_FOR_LOOP_VECTOR_CHECK(v0,v1,v2,v3,v4) sf_debug_for_loop_vector_check(sfGlobalDebugInstanceStruct,v0,v1,v2,v3,v4) - #define _SFD_RUNTIME_ERROR_MSGID(v0) sf_debug_runtime_error_msgid(sfGlobalDebugInstanceStruct,v0) - #define _SFD_OVERFLOW_DETECTION(sfDebugOverflowType,sfDebugObjectTypeEnum,ssId,length,offset,objectNumber,activeEventNumber,isFasterRuntimeOn) sf_debug_overflow_detection(sfGlobalDebugInstanceStruct,\ - sfDebugOverflowType, CHARTINSTANCE_INSTANCENUMBER, sfDebugObjectTypeEnum,\ - (unsigned int)ssId, length, offset, (unsigned int)objectNumber,(int)activeEventNumber,_sfTime_,(bool)isFasterRuntimeOn) diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.c b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.c deleted file mode 100644 index 6bcda9213335be20a9fd24e77d8c10ce166fed0f..0000000000000000000000000000000000000000 --- a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.c +++ /dev/null @@ -1,287 +0,0 @@ -#include "test_model_sfun.h" -#include "sf_runtime/sfcdebug.h" - -struct SfDebugInstanceStruct; -struct SfDebugInstanceStruct* sfGlobalDebugInstanceStruct = NULL; - -#define PROCESS_MEX_SFUNCTION_CMD_LINE_CALL - -unsigned int sf_process_check_sum_call( int nlhs, mxArray * plhs[], int nrhs, - const mxArray * prhs[] ) -{ - extern unsigned int sf_test_model_process_check_sum_call( int nlhs, mxArray * - plhs[], int nrhs, const mxArray * prhs[] ); - if (sf_test_model_process_check_sum_call(nlhs,plhs,nrhs,prhs)) - return 1; - return 0; -} - -unsigned int sf_process_autoinheritance_call( int nlhs, mxArray * plhs[], int - nrhs, const mxArray * prhs[] ) -{ - extern unsigned int sf_test_model_autoinheritance_info( int nlhs, mxArray * - plhs[], int nrhs, const mxArray * prhs[] ); - char commandName[64]; - char machineName[128]; - if (nrhs < 4) { - return 0; - } - - if (!mxIsChar(prhs[0]) || !mxIsChar(prhs[1])) - return 0; - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_autoinheritance_info")) - return 0; - mxGetString(prhs[1], machineName,sizeof(machineName)/sizeof(char)); - machineName[(sizeof(machineName)/sizeof(char)-1)] = '\0'; - if (strcmp(machineName, "test_model") == 0) { - const mxArray *newRhs[3] = { NULL, NULL, NULL }; - - newRhs[0] = prhs[0]; - newRhs[1] = prhs[2]; - newRhs[2] = prhs[3]; - return sf_test_model_autoinheritance_info(nlhs,plhs,3,newRhs); - } - - return 0; -} - -unsigned int sf_process_get_third_party_uses_info_call( int nlhs, mxArray * - plhs[], int nrhs, const mxArray * prhs[] ) -{ - extern unsigned int sf_test_model_third_party_uses_info( int nlhs, mxArray * - plhs[], int nrhs, const mxArray * prhs[] ); - char commandName[64]; - char machineName[128]; - if (nrhs < 4) { - return 0; - } - - if (!mxIsChar(prhs[0]) || !mxIsChar(prhs[1])) - return 0; - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_third_party_uses_info")) - return 0; - mxGetString(prhs[1], machineName,sizeof(machineName)/sizeof(char)); - machineName[(sizeof(machineName)/sizeof(char)-1)] = '\0'; - if (strcmp(machineName, "test_model") == 0) { - const mxArray *newRhs[3] = { NULL, NULL, NULL }; - - newRhs[0] = prhs[0]; - newRhs[1] = prhs[2]; - newRhs[2] = prhs[3]; - return sf_test_model_third_party_uses_info(nlhs,plhs,3,newRhs); - } - - return 0; -} - -unsigned int sf_process_get_jit_fallback_info_call( int nlhs, mxArray * plhs[], - int nrhs, const mxArray * prhs[] ) -{ - extern unsigned int sf_test_model_jit_fallback_info( int nlhs, mxArray * plhs[], - int nrhs, const mxArray * prhs[] ); - char commandName[64]; - char machineName[128]; - if (nrhs < 4) { - return 0; - } - - if (!mxIsChar(prhs[0]) || !mxIsChar(prhs[1])) - return 0; - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_jit_fallback_info")) - return 0; - mxGetString(prhs[1], machineName,sizeof(machineName)/sizeof(char)); - machineName[(sizeof(machineName)/sizeof(char)-1)] = '\0'; - if (strcmp(machineName, "test_model") == 0) { - const mxArray *newRhs[3] = { NULL, NULL, NULL }; - - newRhs[0] = prhs[0]; - newRhs[1] = prhs[2]; - newRhs[2] = prhs[3]; - return sf_test_model_jit_fallback_info(nlhs,plhs,3,newRhs); - } - - return 0; -} - -unsigned int sf_process_get_updateBuildInfo_args_info_call( int nlhs, mxArray * - plhs[], int nrhs, const mxArray * prhs[] ) -{ - extern unsigned int sf_test_model_updateBuildInfo_args_info( int nlhs, mxArray - * plhs[], int nrhs, const mxArray * prhs[] ); - char commandName[64]; - char machineName[128]; - if (nrhs < 4) { - return 0; - } - - if (!mxIsChar(prhs[0]) || !mxIsChar(prhs[1])) - return 0; - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_updateBuildInfo_args_info")) - return 0; - mxGetString(prhs[1], machineName,sizeof(machineName)/sizeof(char)); - machineName[(sizeof(machineName)/sizeof(char)-1)] = '\0'; - if (strcmp(machineName, "test_model") == 0) { - const mxArray *newRhs[3] = { NULL, NULL, NULL }; - - newRhs[0] = prhs[0]; - newRhs[1] = prhs[2]; - newRhs[2] = prhs[3]; - return sf_test_model_updateBuildInfo_args_info(nlhs,plhs,3,newRhs); - } - - return 0; -} - -unsigned int sf_process_get_eml_resolved_functions_info_call( int nlhs, mxArray * - plhs[], int nrhs, const mxArray * prhs[] ) -{ - extern unsigned int sf_test_model_get_eml_resolved_functions_info( int nlhs, - mxArray * plhs[], int nrhs, const mxArray * prhs[] ); - char commandName[64]; - char machineName[128]; - if (nrhs < 3) { - return 0; - } - - if (!mxIsChar(prhs[0]) || !mxIsChar(prhs[1])) - return 0; - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"get_eml_resolved_functions_info")) - return 0; - mxGetString(prhs[1], machineName,sizeof(machineName)/sizeof(char)); - machineName[(sizeof(machineName)/sizeof(char)-1)] = '\0'; - if (strcmp(machineName, "test_model") == 0) { - const mxArray *newRhs[2] = { NULL, NULL }; - - newRhs[0] = prhs[0]; - newRhs[1] = prhs[2]; - return sf_test_model_get_eml_resolved_functions_info(nlhs,plhs,2,newRhs); - } - - return 0; -} - -unsigned int sf_mex_unlock_call( int nlhs, mxArray * plhs[], int nrhs, const - mxArray * prhs[] ) -{ - char commandName[20]; - if (nrhs<1 || !mxIsChar(prhs[0]) ) - return 0; - mxGetString(prhs[0], commandName,sizeof(commandName)/sizeof(char)); - commandName[(sizeof(commandName)/sizeof(char)-1)] = '\0'; - if (strcmp(commandName,"sf_mex_unlock")) - return 0; - while (mexIsLocked()) { - mexUnlock(); - } - - return(1); -} - -extern unsigned int sf_debug_api(struct SfDebugInstanceStruct* debugInstance, - int nlhs, mxArray * plhs[], int nrhs, const mxArray * prhs[] ); -static unsigned int sf_debug_api_wrapper( int nlhs, mxArray * plhs[], int nrhs, - const mxArray * prhs[] ) -{ - return sf_debug_api(sfGlobalDebugInstanceStruct, nlhs, plhs, nrhs, prhs); -} - -static unsigned int ProcessMexSfunctionCmdLineCall(int nlhs, mxArray * plhs[], - int nrhs, const mxArray * prhs[]) -{ - if (sf_debug_api_wrapper(nlhs,plhs,nrhs,prhs)) - return 1; - if (sf_process_check_sum_call(nlhs,plhs,nrhs,prhs)) - return 1; - if (sf_mex_unlock_call(nlhs,plhs,nrhs,prhs)) - return 1; - if (sf_process_autoinheritance_call(nlhs,plhs,nrhs,prhs)) - return 1; - if (sf_process_get_third_party_uses_info_call(nlhs,plhs,nrhs,prhs)) - return 1; - if (sf_process_get_jit_fallback_info_call(nlhs,plhs,nrhs,prhs)) - return 1; - if (sf_process_get_updateBuildInfo_args_info_call(nlhs,plhs,nrhs,prhs)) - return 1; - if (sf_process_get_eml_resolved_functions_info_call(nlhs,plhs,nrhs,prhs)) - return 1; - mexErrMsgTxt("Unsuccessful command."); - return 0; -} - -static unsigned int sfGlobalMdlStartCallCounts = 0; -unsigned int sf_machine_global_initializer_called(void) -{ - return(sfGlobalMdlStartCallCounts > 0); -} - -extern unsigned int sf_test_model_method_dispatcher(SimStruct *S, unsigned int - chartFileNumber, const char* specsCksum, int_T method, void *data); -unsigned int sf_machine_global_method_dispatcher(SimStruct *simstructPtr, const - char *machineName, unsigned int chartFileNumber, const char* specsCksum, int_T - method, void *data) -{ - if (!strcmp(machineName,"test_model")) { - return(sf_test_model_method_dispatcher(simstructPtr,chartFileNumber, - specsCksum,method,data)); - } - - return 0; -} - -extern void test_model_terminator(void); -void sf_machine_global_terminator(SimStruct* S) -{ - sfGlobalMdlStartCallCounts--; - if (sfGlobalMdlStartCallCounts == 0) { - test_model_terminator(); - sf_debug_terminate(sfGlobalDebugInstanceStruct); - sfGlobalDebugInstanceStruct = NULL; - } - - return; -} - -extern void test_model_initializer(void); -extern void test_model_register_exported_symbols(SimStruct* S); -extern void test_model_debug_initialize(struct SfDebugInstanceStruct*); -void sf_register_machine_exported_symbols(SimStruct* S) -{ - test_model_register_exported_symbols(S); -} - -bool callCustomFcn(char initFlag) -{ - return false; -} - -void sf_machine_global_initializer(SimStruct* S) -{ - bool simModeIsRTWGen = sim_mode_is_rtw_gen(S); - sfGlobalMdlStartCallCounts++; - if (sfGlobalMdlStartCallCounts == 1) { - if (simModeIsRTWGen) { - sf_register_machine_exported_symbols(S); - } - - sfGlobalDebugInstanceStruct = sf_debug_create_debug_instance_struct(); - if (!simModeIsRTWGen) { - test_model_debug_initialize(sfGlobalDebugInstanceStruct); - } - - test_model_initializer(); - } - - return; -} - -#include "sf_runtime/stateflow_mdl_methods.stub" diff --git a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.obj b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.obj deleted file mode 100644 index a0a5902cd0297abc1f96246ea25fe03fde04dbdb..0000000000000000000000000000000000000000 Binary files a/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.obj and /dev/null differ diff --git a/controls/model/mahony_filter.slx b/controls/model/mahony_filter.slx new file mode 100644 index 0000000000000000000000000000000000000000..df7f4d681d0169f6630f5a48695e21cf85f1de8b Binary files /dev/null and b/controls/model/mahony_filter.slx differ diff --git a/controls/model/modelParameters.m b/controls/model/modelParameters.m index bda6e93514a28d95838ee3a62e6ded80d694facf..20dad9510c22a96dec30005120ada0f9c7aebd34 100644 --- a/controls/model/modelParameters.m +++ b/controls/model/modelParameters.m @@ -1,5 +1,4 @@ -temp = 1; -% Log Analysis Toggle +% Log Analysis Toggle logAnalysisToggle = 1; % 1 for log analysis, 0 for normal operation % Define Simulink Runtime (if logAnalysisToggle is selected, this will be @@ -7,28 +6,28 @@ temp = 1; runtime = 20; % Model Parameters - m = 1.244; % Quadrotor + battery mass + m = 1.140; % Quadrotor + battery mass g = 9.81; % Acceleration of gravity Jxx = 0.0130; % Quadrotor and battery motor of inertia around bx (pitch) Jyy = 0.0140; % Quadrotor and battery motor of inertia around by (roll) Jzz = 0.0285; % Quadrotor and battery motor of inertia around bz (yaw) Jreq = 4.2012e-05; % Rotor and motor moment of inertia around axis of rotation - Kt = 8.6519e-6; % Rotor thrust constant + Kt = 1.2007e-05; % Rotor thrust constant Kh = 0; % Rotor in-plane drag constant - Kd = 1.0317e-7; % Rotor 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 Rm = 0.2308; % Motor resistance Kq = 96.3422; % Motor torque constant Kv = 96.3422; % Motor back emf constant - If = 0.511; % Motor internal friction current + If = 0.3836; % Motor internal friction current Pmin = 1e5; % Minimum zybo output duty cycle command Pmax = 2e5; % Maximum zybo output duty cycle command Tc = 0.04; % Camera system sampling period Tq = 0.005; % Quad sampling period tau_c = 0; % Camera system total latency - Vb = 11.1; % Nominal battery voltage (V) + Vb = 11.4; % Nominal battery voltage (V) x_controlled_o = 0; % Equilibrium lateral controller output y_controlled_o = 0; % Equilibrium longitudinal controller output yaw_controlled_o = 0; % Equilibrium yaw controller output @@ -42,11 +41,11 @@ temp = 1; omega3_o = sqrt((m*g)/(4*Kt)); % Equilibrium height controller output - height_controlled_o = (((Rm*If + ... - + (((omega0_o * 2 * Rm * Kv * Kq ... + height_controlled_o = (((Rm*If ... + + (((omega0_o * 2 * Rm * Kv * Kq ... * Kd + 1)^2) - 1)/(4* Rm*Kv^2*Kq ... - *Kd))/Vb)*(Pmax- Pmin)+Pmin); - + * Kd))/Vb)*(Pmax - Pmin) + Pmin); + % Equilibrium positions x_o = 0; y_o = 0; @@ -67,112 +66,7 @@ temp = 1; pitchrate_o = 0; yawrate_o = 0; -% Import Data and determine errors -if logAnalysisToggle == 1 && temp == 0 - % Import Data to Workspace - data = importdata('loggingAnalysis/logFiles/logData.csv'); - - % Set up time vector - time = data.data(:, 1); - runtime = max(time); - - % Determine x position error - x_setpoint = data.data(:, 25); - x_position = data.data(:, 20); - x_error = timeseries(x_setpoint - x_position, time); - - % Determine y position error - y_setpoint = data.data(:, 26); - y_position = data.data(:, 21); - y_error = timeseries(y_setpoint - y_position, time); - - % Determine z position error - z_setpoint = data.data(:, 27); - z_position = data.data(:, 22); - z_error = timeseries(z_setpoint - z_position, time); - - % Determine pitch error - pitch_setpoint = data.data(:, 9); - pitch_value = data.data(:, 23); - pitch_error = timeseries(pitch_setpoint - pitch_value, time); - - % Determine roll error - roll_setpoint = data.data(:, 10); - roll_value = data.data(:, 24); - roll_error = timeseries(roll_setpoint - roll_value, time); - - % Determine yaw error - yaw_setpoint = zeros(length(time), 1); % NEEDS UPDATED WHEN LOG FILE INCLUDES YAW SETPOINT - yaw_value = data.data(:,10);%(length(time), 1); % NEEDS UPDATED WHEN LOG FILE INCLUDES YAW VALUE - yaw_error = timeseries(yaw_setpoint - yaw_value, time); - - % Determine pitch rate error - pitchrate_setpoint = data.data(:, 11); - pitchrate_value = data.data(:, 6); - pitchrate_error = timeseries(pitchrate_setpoint - pitchrate_value, time); - - % Determine roll rate error - rollrate_setpoint = data.data(:, 12); - rollrate_value = data.data(:, 5); - rollrate_error = timeseries(rollrate_setpoint - rollrate_value, time); - - % Determine yaw rate error - yawrate_setpoint = data.data(:, 13); - yawrate_value = data.data(:, 7); - yawrate_error = timeseries(yawrate_setpoint - yawrate_value, time); - - % Pull motor commands from log - x_command = data.data(:, 14); - y_command = data.data(:, 15); - z_command = data.data(:, 8); - yaw_command = data.data(:, 16); - - % Determine signal mix PWM values - PWM0 = data.data(:, 28); - PWM1 = data.data(:, 29); - PWM2 = data.data(:, 30); - PWM3 = data.data(:, 31); - - % Determine the initial height controller command - % height_controlled_o = 1; % NEEDS UPDATED WHEN LOG FILES INCLUDE THROTTLE COMMAND - - % Determine the initial rotor speeds based on PWM inputs - u_P0 = (PWM0(1) - Pmin) / (Pmax - Pmin); - u_P1 = (PWM1(1) - Pmin) / (Pmax - Pmin); - u_P2 = (PWM2(1) - Pmin) / (Pmax - Pmin); - u_P3 = (PWM3(1) - Pmin) / (Pmax - Pmin); - - Vb_eff_0 = u_P0 * Vb; - Vb_eff_1 = u_P1 * Vb; - Vb_eff_2 = u_P2 * Vb; - Vb_eff_3 = u_P3 * Vb; - - omega0_o = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*( Kv*Rm*If - Kv*Vb_eff_0))) / (2*Rm*Kv*Kq*Kd); - omega1_o = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*( Kv*Rm*If - Kv*Vb_eff_1))) / (2*Rm*Kv*Kq*Kd); - omega2_o = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*( Kv*Rm*If - Kv*Vb_eff_2))) / (2*Rm*Kv*Kq*Kd); - omega3_o = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*( Kv*Rm*If - Kv*Vb_eff_3))) / (2*Rm*Kv*Kq*Kd); - - % Determine initial positions for x, y, and z - x_o = x_position(1); - y_o = y_position(1); - z_o = z_position(1); - - % Determine initial velocity for x, y, and z - x_vel_o = (x_position(2) - x_position(1)) / (time(2) - time(1)); - y_vel_o = (y_position(2) - y_position(1)) / (time(2) - time(1)); - z_vel_o = (z_position(2) - z_position(1)) / (time(2) - time(1)); - - % Determine initial angles - roll_o = roll_value(1); - pitch_o = pitch_value(1); - yaw_o = yaw_value(1); - - % Determine initial angular rates - rollrate_o = rollrate_value(1); - pitchrate_o = pitchrate_value(1); - yawrate_o = yawrate_value(1); - -elseif logAnalysisToggle == 1 && temp == 1 +if logAnalysisToggle == 1 %%%%%% Commented out section until logging is .txt file based %%%%%% % FNAME % if you know the name of the log file that you want to parse, set the it @@ -195,6 +89,12 @@ elseif logAnalysisToggle == 1 && temp == 1 [dataStruct, headers] = parse_log_model(params.file.pathName); time = dataStruct.Time.data; + time = time - time(1); + time_indices = length(time); + +% time = 0:0.005001:max(time); +% time = time(1:time_indices); + runtime = max(time); % Determine x position error @@ -214,12 +114,12 @@ elseif logAnalysisToggle == 1 && temp == 1 % Determine pitch error pitch_setpoint = dataStruct.X_pos_PID_Correction.data; - pitch_value = dataStruct.VRPN_Pitch_Constant.data; + pitch_value = dataStruct.Pitch_Constant.data; pitch_error = timeseries(pitch_setpoint - pitch_value, time); % Determine roll error roll_setpoint = dataStruct.Y_pos_PID_Correction.data; - roll_value = dataStruct.VRPN_Roll_Constant.data; + roll_value = dataStruct.Roll_Constant.data; roll_error = timeseries(roll_setpoint - roll_value, time); % Determine yaw error @@ -253,7 +153,72 @@ elseif logAnalysisToggle == 1 && temp == 1 PWM1 = dataStruct.Signal_Mixer_PWM_1.data; PWM2 = dataStruct.Signal_Mixer_PWM_2.data; PWM3 = dataStruct.Signal_Mixer_PWM_3.data; - -end - - + PWM_arr = ... + [PWM0, PWM1, PWM2, PWM3]; + motor_commands = timeseries(PWM_arr, time); + + % Pull the measurements from the acceleratometer + raw_accel_data_x = dataStruct.accel_x.data; + raw_accel_data_y = dataStruct.accel_y.data; + raw_accel_data_z = dataStruct.accel_z.data; + raw_accel_data_arr = ... + [ raw_accel_data_x , raw_accel_data_y , raw_accel_data_z ]; + raw_accel_data = timeseries( raw_accel_data_arr , time ); + + % Pull the measurements from the gyroscope + raw_gyro_data_x = dataStruct.gyro_x.data; + raw_gyro_data_y = dataStruct.gyro_y.data; + raw_gyro_data_z = dataStruct.gyro_z.data; + raw_gyro_data_arr = ... + [ raw_gyro_data_x , raw_gyro_data_y , raw_gyro_data_z ]; + raw_gyro_data = timeseries( raw_gyro_data_arr , time ); + + % Create time series object for z command + throttle_command = timeseries(dataStruct.RC_Throttle_Constant.data, time); + z_command = dataStruct.RC_Throttle_Constant.data; + + % Pull the measurements from the complimentary filter + pitch_measured_IMU = dataStruct.Pitch_Constant.data; + roll_measured_IMU = dataStruct.Roll_Constant.data; + IMU_angle_arr = ... + [roll_measured_IMU, pitch_measured_IMU]; + IMU_angle_data = timeseries( IMU_angle_arr, time); + + % Pull VRPN pitch and roll + pitch_measured_VRPN = dataStruct.VRPN_Pitch_Constant.data; + roll_measured_VRPN = dataStruct.VRPN_Roll_Constant.data; + + % Set height_controlled_o to initial throttle command + height_controlled_o = dataStruct.RC_Throttle_Constant.data(1); + + % Set rotor speed initial conditions to there calculated values based on + % initial throttle control + omega0_o = (sqrt(((height_controlled_o ... + - Pmin)/(Pmax - Pmin)* Vb - Rm * If) * 4 * ... + Rm * Kv^2 * Kq * Kd + 1) - 1) / (2 * Rm * ... + Kv * Kq * Kd); + omega1_o = omega0_o; + omega2_o = omega0_o; + omega3_o = omega0_o; + + % Set initial positions + x_o = x_position(1); + y_o = y_position(1); + z_o = z_position(1); + + % Set initial velocities + x_vel_o = (x_position(1) - x_position(2))/(time(1) - time(2)); + y_vel_o = (y_position(1) - y_position(2))/(time(1) - time(2)); + z_vel_o = (z_position(1) - z_position(2))/(time(1) - time(2)); + + % Equilibrium angles + roll_o = roll_measured_VRPN(1); + pitch_o = pitch_measured_VRPN(1); + yaw_o = 0; + + % Equilibrium angular rates + rollrate_o = (roll_measured_VRPN(1) - roll_measured_VRPN(2))/(time(1) - time(2)); + pitchrate_o = (pitch_measured_VRPN(1) - pitch_measured_VRPN(2))/(time(1) - time(2)); + yawrate_o = 0; + +end \ No newline at end of file diff --git a/controls/model/parse_log_model.m b/controls/model/parse_log_model.m index 59aef835bd0d5077e9619b7c02880a8390d95643..cb7cd4aa2d95314e075ed4129ea2e723c30405a1 100644 --- a/controls/model/parse_log_model.m +++ b/controls/model/parse_log_model.m @@ -1,4 +1,4 @@ -function [loggedData, headers] = parse_log_model(filename, params, expData) +function [loggedData, headers] = parse_log_model(filename) %parse_log This independent function parses the data stored in the file and %returns a structure containing the data % filename - this is the complete path of the file with the filename diff --git a/controls/model/test_model.slx b/controls/model/test_model.slx index 93229cbac59b18930c7e4a1158b9e2f6c53bb53c..56971125dc1d50445e083b3e0f8b6d3187957d3b 100644 Binary files a/controls/model/test_model.slx and b/controls/model/test_model.slx differ diff --git a/documentation/.gitkeep b/documentation/.gitkeep new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/documentation/ci_faq.md b/documentation/ci_faq.md new file mode 100644 index 0000000000000000000000000000000000000000..679e0b9f484603505d1e64bd4c57369b255becc7 --- /dev/null +++ b/documentation/ci_faq.md @@ -0,0 +1,40 @@ +# Continuous Integration (CI) FAQ + +## Why did my commit fail CI? +On every commit, a script runs that performs a number of things, including +compiling code and running unit and functional tests. Whatever you did +apparently broke one of these things. + +## Why should I care about the CI results? +CI _immensely_ streamlines the development cycle by helping us catch bugs +immediately, allowing us to fix them early before they plague us (or future +users of the code base). It's a common industry practice. If you break the CI +pipeline, don't ignore it! Try your best to get the branch back in working +condition. + +## Okay, so my commit failed CI, and I guess I care. What should I do? +1. Re-run the build. + - Sometimes something weird happens, so it's good to check this. +2. Figure out what you did wrong and fix it. + - If you click on the build, you should be able to see the exact logs the + build process. Debug the error to figure out what went wrong. Maybe you + failed a test. You may need to open the source code for the test to see + where you failed, which is very insightful into figuring out what went + wrong. +3. Figure out what CI is doing wrong. + - Sometimes a test might be poorly designed. At this point, it can be really + tempting to just ignore the build failure altogether (don't do that!), or + just remove the broken test (not as bad, but still don't do that). The best + thing is to fix the test so that we continue to have good regression + test coverage over our code. + +## How does CI work? +When a commit is added to a branch in our repository, a notification is sent out +to our gitlab-ci-runner, which instructs it to checkout the updated branch and +run the directive in `.gitlab-ci.yml`. It then runs each directive, which is +made up of bash scripts to execute. In our case, we run two scripts, +`ci-build.sh` and `ci-test.sh`, which compile projects and run checks, +respectively. (Look at these scripts to learn more about how they work). If +some error occurs during the script (perhaps a forced error generated by a +failed test), then the runner sends a message back to Gitlab indicating that the +CI failed. Otherwise, it succeeds. diff --git a/documentation/how_to_calibrate_the_camera_system.md b/documentation/how_to_calibrate_the_camera_system.md new file mode 100644 index 0000000000000000000000000000000000000000..a04a5fb1f9e69c76c90b9c76f9bbbd5c428ae53a --- /dev/null +++ b/documentation/how_to_calibrate_the_camera_system.md @@ -0,0 +1,24 @@ +# How to calibration the camera system + +*This tutorial is in a draft state* + +On the computer Coover 3050-07, open the Tracking Tools program. + +1. Click the "Camera Calibration" button. (It is a picture of a wand). +2. Get the calibration wand (on top of cabinet). Ensure the calibration wand is REMOVED from the viewing area. +3. Click "Start Wanding". + 4. If you get a message about reflective materials being seen, click "Block". +5. Click "Start Wanding" again. +6. Start painting + +Look at each individual camera sample count, and ensure each camera has a sufficient number. Also look at the generic "sufficient for quality" indicator. Try to get samples data points for all areas of the viewing area. + +Last time, we tried to get the sufficient quality at "very high" and each camera sample count over 10,000. + +After you finished, click "Apply Result". + +Then click "apply and refine" and save. + +Next, you'll be calibrating the floor. Then use the L-tool with the trackables (in the cabinet). In order to get the z-axis pointing vertically, you'll need to pinch the L-tool so that it sits upright on the floor (we used bricks). You can use a level to ensure it is stable. + +Click "Set Ground Plane". \ No newline at end of file diff --git a/documentation/how_to_charge_lipo.md b/documentation/how_to_charge_lipo.md new file mode 100644 index 0000000000000000000000000000000000000000..662752226360a306f954dfb95996368a692a952d --- /dev/null +++ b/documentation/how_to_charge_lipo.md @@ -0,0 +1,21 @@ +# How to charge the LiPo batteries + +This tutorial includes instructions to safely charge the Li-Po battery. The quadcopter uses a 3S Li-Po battery with 11.1V nominal voltage. + +1. Start by turning on the charging station’s power supply, which should be on the left side of the charging station. The power supply should be at 17 volts. +  +2. On the charging station: + - Connect the balancer (connector with many white slots) and the charging cable (yellow connector) to the charging station. +  + - Cycle through (Hit “Enter†and use “Up†and “down†to cycle) the memory banks until you find the correct setting for the battery you are using. The one in this demonstration is a LiPo with nominal voltage of 11.1V and a capacity of 2200 mah. The correct settings for this battery is located under memory no. 6. +3. Connect the battery to the balancer and charging cable. Plug the balancer into the slot corresponding the number of cells the battery has. In this case the battery is 3 cells so you would plug it into the 3S balancer slot. +  +4. Hold “Enter†on the charging station until it prompts you for “Charge Start Solo Modeâ€. Hold “Enter†again to check and confirm the battery’s voltage and cell count. +  +  +5. Press “Enter†to start the charging process. +  +6. When the battery is done charging the charging station will make a continuous ringing sound. The screen on the charging station will say “LiPo End/CHGâ€. Hold “Enter†to return to the main menu. Unplug the battery from the charging cable and the balancer. Power off the charging station’s power supply. +  + + diff --git a/documentation/how_to_demo.md b/documentation/how_to_demo.md new file mode 100644 index 0000000000000000000000000000000000000000..104c64bc20852f6dcbcb9bea5a1c380d6bae8d63 --- /dev/null +++ b/documentation/how_to_demo.md @@ -0,0 +1,100 @@ +# How to demo the quadcopter + +Follow this How-To to get the quadcopter up and running in Coover 3050. + +**Table of Contents** + +[[_TOC_]] + +## Setup Infrared Camera System + +1. To start up the camera system, log into the camera system computer (co3050-07) with the following username and password: + + username: `.\microcart`<br> + password: `microcart` (this might be wrong...) + +2. Once the OS is done loading, start up the program "Tracking Tools". +3. From the startup window, choose "Open existing project" +4. Choose "TrackingToolsProject 2017-01-13 5.30pm" in the "Optitrack_Configuration" folder +6. Then go to File -> Open and choose "Microcart" in the "Optitrack_Configuration" folder + - This should create a "UAV" under "Trackables" in the Project Explorer on the left side of the screen +7. Now you should be able to move the quadcopter trackable around in the tracking area, and see it update in real-time on the screen. + +## Setup Ground Station +On the ground station computer (Co3050-09), log in with the following credentials. + +username: `ucart`<br> +password: `microcart` + +Navigate to the ground station folder in a Terminal. +```bash +$ cd {project_root}/groundStation +$ ls +BackEnd Cli logs Makefile obj README.md src ucart.socket (or something like that) +``` + +If the project hasn't been built in a while, re-make the project: +```bash +make vrpn +make +``` + +And set the wifi environment variable if you want to connect to the quad over wifi. +```bash +$ UCART_USE_WIFI=true +``` + +## Setup Transmitter +The RC transmitter is used to manually control the quad. +1. Ensure the transmitter has the following state before turning it on: + - "Gear" is set to 0 + - "Flap" is set to 1 + - Throttle is set to the lowest position +2. Turn on the transmitter. + +## Setup Quadcopter + +This section assumes the quad already has a prepared boot image inserted into the SD card port and that a properly charged Li-Po battery is ready for use. + +0. Prequisites + 1. Make sure the connection to the motors from the main power line is **disconnected**. + 2. Make sure the previous setup sections have been done prior starting this section +1. Insert the Li-Po battery into the holder beneath the quad, and plug it into the quad. +2. Turn on the Zybo Board using the switch. + 1. The "PGOOD" Light should turn red. + 2. After the program has been completely loaded, the green DONE LED should turn on. +  +3. Ensure the quad and transmitter has connected successfully. + - The RC transmitter should have GAUI 330X selected and displayed on the screen. With the quad and transmitter on, the unit on the quad labeled Spektrum AR610 should have a blinking orange light or solid orange light (It is easier to see the orange light from the top of the receiver). If this is not blinking or solid, try restarting the quad and transmitter with the transmitter closer to the quad. +  +  + +4. Plug connect the motors to the main power line. + +## Start the Ground Station (CLI) +Execute the following on the ground station from the root of the ground station folder. + +In one terminal, run the backend: +```bash +UCART_SOCKET=./ucart.socket ./BackEnd +``` + +In another terminal, run the monitor: +```bash +UCART_SOCKET=./ucart.socket ./Cli monitor -f +``` + +Finally, in another terminal, export the socket path, and then execute any CLI commands that you like: +```bash +export UCART_SOCKET=./ucart.socket +./Cli setpid --pitch -p 1.000 +# ... other CLI commands +``` + +## Start the Quad +1. Using the transmitter, flip the "Gear" switch to 1. + 1. You should see the green LED4 MIO7 turn on. +2. Start flying the quad. Below is a summary of how the manual controls work. +  + + diff --git a/documentation/how_to_document_things_on_gitlab.md b/documentation/how_to_document_things_on_gitlab.md new file mode 100644 index 0000000000000000000000000000000000000000..86e6fd1774048a3bc79bfe2b65c51544fc87daf3 --- /dev/null +++ b/documentation/how_to_document_things_on_gitlab.md @@ -0,0 +1,34 @@ +# Documentation on Gitlab +We can use Gitlab to host our documentation by exploiting the fact that Gitlab +automatically renders Markdown (.md) files as HTML in the browser, making it +easy to read and show images. + +# Organization +We will be using the top-level `README.md` as our main page for documentation. +You might notice that this page is automatically rendered on our [main Gitlab +project page](/../). + +Ideally, all documentation should be reachable from links on this main page. +For documentation that is while-project encompassing, those links should go +on the main page itself. For documentation that is sub-topic specific (quad, +ground station, controls), add an appropriate link on the sub topic's README.md +page. See the Quad section for an example. + +Ideally, all Markdown (.md) files should go inside some `doc` or `documentation` +folder (with exception to the READMEs). + +# Editing +If you are familiar with Markdown and Git, you can just edit the documentation +from within your normal Git workflow. + +However, Gitlab also makes is relatively easy to edit Markdown pages for +documentation right in the browser. To edit a Markdown page, select "Edit" at +the top right. This will bring up an editor that you can use to make changes. +To preview the final project, use the "Preview" tab at the top left. To achieve +desired formatting, you will need to use the Markdown syntax - see the [Gitlab +Markdown reference](https://docs.gitlab.com/ee/user/markdown.html). + +To create a new file within Gitlab, go to the "Repository" tab and then "Files" +tab. As you navigate through our files, you will see a "+" (plus sign) button. +From here, you can create a new Markdown file, upload a new file, or create a +folder (say if you need to create some `doc` folder). diff --git a/documentation/images/.gitkeep b/documentation/images/.gitkeep new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/groundStation/Makefile b/groundStation/Makefile index b9024633ab737dd19d47c447fb11cda30624cf95..c3970786e8e22cf7f21643be048600d022e2ee61 100644 --- a/groundStation/Makefile +++ b/groundStation/Makefile @@ -7,7 +7,7 @@ CFLAGS= -Wall -pedantic -Wextra -Werror -std=gnu99 -g -Wno-unused-parameter -Wno CXXFLAGS= -Wall -pedantic -Wextra -Werror -Wno-reorder -Wno-unused-variable -std=c++0x -g INCLUDES = $(foreach dir, $(INCDIR), -I$(dir)) INCDIR= src/vrpn src/vrpn/quat src/vrpn/build $(BESRCDIR) $(CLISRCDIR) $(FESRCDIR) ../quad/inc -LIBS= -lpthread -lbluetooth -lvrpn -lquat -Lsrc/vrpn/build -Lsrc/vrpn/build/quat -L../quad/lib -lquad_app -lcommands -lgraph_blocks -lcomputation_graph +LIBS= -lpthread -lbluetooth -lvrpn -lquat -Lsrc/vrpn/build -Lsrc/vrpn/build/quat -L../quad/lib -lquad_app -lcommands -lgraph_blocks -lcomputation_graph -lm OBJDIR=obj # Backend Specific Variables diff --git a/groundStation/README.md b/groundStation/README.md index 2e6be4d83774dc08d23ac744b70eba6ce44be294..e14675ab8ad6eb0b870f87355b94a0778eae994c 100644 --- a/groundStation/README.md +++ b/groundStation/README.md @@ -62,4 +62,25 @@ or alternatively with symlinks This will fetch the block_id, type_id and name of every node in the current graph -You can run any number of any combination of frontend tools at the same time. \ No newline at end of file +You can run any number of any combination of frontend tools at the same time. + +### Batch Update of PID constants +The CLI only supports setting one PID constant at a time using the following command. + +From the `groundStation` folder: +``` +./Cli setpid --pitch -p 1.000 +``` + +This can get tedious for 27 PID constants. + +To help, we made a batch script that allows you to easily set all 27 PID constants at once and save your progress as you go. + +First, edit the `parameters.txt` file in the `groundStation/scripts` folder to specify the values you want to set. The script will parse this file and pass them to the `Cli` program. + +Then simply run the script from the `groundStation` folder: +``` +scripts/setpid_batch.sh +``` + +Remember to commit your changes in the `parameters.txt` file if you believe you have found a better default state for the quad. \ No newline at end of file diff --git a/groundStation/scripts/bypass_kill_switch.sh b/groundStation/scripts/bypass_kill_switch.sh new file mode 100755 index 0000000000000000000000000000000000000000..183df7b8e30d642e0bf92b8a0fbc7b1ef1949e7f --- /dev/null +++ b/groundStation/scripts/bypass_kill_switch.sh @@ -0,0 +1,13 @@ +#! /bin/bash + +if [ -z "$1" ]; then + echo "No argument supplied" + exit 0 +fi +cd .. +while true ; do + ./setparam 37 0 $1 + sleep 0.4 + ./setparam 37 0 $(( $1 - 1 )) + sleep 0.4 +done diff --git a/groundStation/scripts/eric.sh b/groundStation/scripts/eric.sh new file mode 100755 index 0000000000000000000000000000000000000000..7a9d0e2892ee80bba467bebbe0c60987b493f6fa --- /dev/null +++ b/groundStation/scripts/eric.sh @@ -0,0 +1,34 @@ +#!/bin/bash + +./setparam 18 0 0.045 +#inner loop +./setparam 'roll rate pid' 'kp' 3000 +./setparam 'roll rate pid' 'ki' 0 +./setparam 'roll rate pid' 'kd' 500 +./setparam 'roll rate pid' 'alpha' 0.88 + +./setparam 'pitch rate pid' 'kp' 3000 +./setparam 'pitch rate pid' 'ki' 0 +./setparam 'pitch rate pid' 'kd' 500 +./setparam 'pitch rate pid' 'alpha' 0.88 + +./setparam 'roll pid' 'kp' 50 +./setparam 'roll pid' 'ki' 0 +./setparam 'roll pid' 'kd' 1 +./setparam 'roll pid' 'alpha' 0.88 + +./setparam 'pitch pid' 'kp' 50 +./setparam 'pitch pid' 'ki' 0 +./setparam 'pitch pid' 'kd' 1 +./setparam 'pitch pid' 'alpha' 0.88 + +#outer loop +./setparam 'X pos PID' 'kp' -0.015 +./setparam 'X pos PID' 'ki' -0 +./setparam 'X pos PID' 'kd' -0.25 +./setparam 'X pos PID' 'alpha' 0.88 + +./setparam 'Y pos PID' 'kp' 0.015 +./setparam 'Y pos PID' 'ki' 0 +./setparam 'Y pos PID' 'kd' 0.25 +./setparam 'Y pos PID' 'alpha' 0.88 diff --git a/groundStation/scripts/parameter.sh b/groundStation/scripts/parameter.sh new file mode 100755 index 0000000000000000000000000000000000000000..316aa17b36c078cc95b268902af85242bcfea632 --- /dev/null +++ b/groundStation/scripts/parameter.sh @@ -0,0 +1,36 @@ +cd .. +./setparam "y pos pid" "kp" 0.015 +./setparam "y pos pid" "ki" 0.005 +./setparam "y pos pid" "kd" 0.03 + +./setparam "x pos pid" "kp" -0.015 +./setparam "x pos pid" "ki" -0.005 +./setparam "x pos pid" "kd" -0.03 + +./setparam "altitude pid" "kp" 9804 +./setparam "altitude pid" "ki" 817 +./setparam "altitude pid" "kd" 7353 + +./setparam "pitch pid" "kp" 4.29 +./setparam "pitch pid" "ki" 0 +./setparam "pitch pid" "kd" 0 + +./setparam "roll pid" "kp" 4.29 +./setparam "roll pid" "ki" 0 +./setparam "roll pid" "kd" 0 + +./setparam "yaw pid" "kp" 2.6 +./setparam "yaw pid" "ki" 0 +./setparam "yaw pid" "kd" 0 + +./setparam "pitch rate pid" "kp" 1138.5 +./setparam "pitch rate pid" "ki" 0 +./setparam "pitch rate pid" "kd" 0 + +./setparam "roll rate pid" "kp" 1138.5 +./setparam "roll rate pid" "ki" 0 +./setparam "roll rate pid" "kd" 0 + +./setparam "yaw rate pid" "kp" 29700 +./setparam "yaw rate pid" "ki" 0 +./setparam "yaw rate pid" "kd" 0 diff --git a/groundStation/scripts/parameterize.sh b/groundStation/scripts/parameterize.sh new file mode 100755 index 0000000000000000000000000000000000000000..591656810626bb7867698124adb50f46bc5e6579 --- /dev/null +++ b/groundStation/scripts/parameterize.sh @@ -0,0 +1,10 @@ +cd .. +./addnode 0 "Zero" +./setparam "zero" 0 0 +./setsource "signal mixer" "pitch" "zero" 0 +./setsource "signal mixer" "roll" "zero" 0 +./setsource "signal mixer" "yaw" "zero" 0 +./addnode 0 "PWM_VAL" +./setparam "pwm_val" 0 100000 +./setsource "signal mixer" "throttle" "pwm_val" 0 + diff --git a/groundStation/scripts/parameters.txt b/groundStation/scripts/parameters.txt deleted file mode 100644 index b59828a078dd77e18f25cc6b2a37763804fa76b5..0000000000000000000000000000000000000000 --- a/groundStation/scripts/parameters.txt +++ /dev/null @@ -1,27 +0,0 @@ -lat p -0.015 -lat i -0.005 -lat d -0.03 -long p 0.015 -long i 0.005 -long d 0.03 -height p 9804.0 -height i 817.0 -height d 7353.0 -pitch p 15.0 -pitch i 0.0 -pitch d 0.2 -roll p 15.0 -roll i 0.0 -roll d 0.2 -yaw p 2.6 -yaw i 0.0 -yaw d 0.0 -pitchv p 4600.0 -pitchv i 0.0 -pitchv d 550 -rollv p 4600.0 -rollv i 0.0 -rollv d 550 -yawv p 435480 -yawv i 0.0 -yawv d 0.0 diff --git a/groundStation/scripts/rate_controller.sh b/groundStation/scripts/rate_controller.sh new file mode 100755 index 0000000000000000000000000000000000000000..fd37f3b5b514c29cb2a501e00b4b4c7f122c49bc --- /dev/null +++ b/groundStation/scripts/rate_controller.sh @@ -0,0 +1,53 @@ +#! /bin/bash + + +./setparam 18 0 0.045 +#inner loop +./setparam 'roll rate pid' 'kp' 3000 +./setparam 'roll rate pid' 'ki' 0 +./setparam 'roll rate pid' 'kd' 500 +./setparam 'roll rate pid' 'alpha' 0.88 + +./setparam 'pitch rate pid' 'kp' 3000 +./setparam 'pitch rate pid' 'ki' 0 +./setparam 'pitch rate pid' 'kd' 500 +./setparam 'pitch rate pid' 'alpha' 0.88 + +./setparam 'roll pid' 'kp' 35 +./setparam 'roll pid' 'ki' 0 +./setparam 'roll pid' 'kd' 1 +./setparam 'roll pid' 'alpha' 0.88 + +./setparam 'pitch pid' 'kp' 35 +./setparam 'pitch pid' 'ki' 0 +./setparam 'pitch pid' 'kd' 1 +./setparam 'pitch pid' 'alpha' 0.88 + +./setparam "X pos PID" "kp" -0.55 +./setparam "X pos PID" "ki" -0.0075 +./setparam "X pos PID" "kd" -0 + +./setparam "Y pos PID" "kp" -0.55 +./setparam "Y pos PID" "ki" -0.0075 +./setparam "Y pos PID" "kd" -0 + +./setparam "Altitude PID" "kp" -9804 +./setparam "Altitude PID" "ki" -817 +./setparam "Altitude PID" "kd" -7353 +./setparam "Altitude PID" "alpha" 0.88 + +./setparam "X vel PID" "kp" 0.1 +./setparam "X vel PID" "kd" 0.02 + +./setparam "X vel" "alpha" 0.88 + +./setparam "Y vel PID" "kp" -0.1 +./setparam "Y vel PID" "kd" -0.02 + +./setparam "y vel" "alpha" 0.88 + +./setparam "x val clamp" 0 -1 +./setparam "x val clamp" 1 1 + +./setparam "y val clamp" 0 -1 +./setparam "y val clamp" 1 1 diff --git a/groundStation/scripts/take_off.sh b/groundStation/scripts/take_off.sh new file mode 100644 index 0000000000000000000000000000000000000000..ae559c6b4d8a29ac7adbb3443e7cdbd0ce951bd4 --- /dev/null +++ b/groundStation/scripts/take_off.sh @@ -0,0 +1,11 @@ +#! /bin/bash + +./setsource "T trim add" "summand 1" "zero" 0 +./setparam "Throttle trim" *wind up value here* + +sleep(1); + +./setsource "T trim add" "summand 1" "Altitude PID" "Correction" +./setparam "Throttle trim" *hover value here* + +./setparam "Alt Setpoint" 0 -0.3 diff --git a/groundStation/src/backend/backend.c b/groundStation/src/backend/backend.c index 5115a25c9919f6fd2a1422d5c5aa962d334d93de..d6b49449d6ca33b2a3727e06d0fdbccc2cfe5696 100644 --- a/groundStation/src/backend/backend.c +++ b/groundStation/src/backend/backend.c @@ -27,6 +27,8 @@ #include <sys/ioctl.h> #include <sys/types.h> #include <netinet/tcp.h> +#include <fcntl.h> +#include <sys/stat.h> //user created includes #include "commands.h" @@ -52,7 +54,6 @@ // function prototypes void readAndPrint(void); void sendVrpnPacket(struct ucart_vrpn_TrackerData *); -void sendStartPacket(void); void getVRPNPacket(struct ucart_vrpn_TrackerData *); void printVrpnData(struct ucart_vrpn_TrackerData *); int connectToZybo(); @@ -89,6 +90,9 @@ char * create_log_name(char * buffer, size_t max); pthread_mutex_t quadSocketMutex; static ssize_t writeQuad(const uint8_t * buf, size_t count); static ssize_t readQuad(char * buf, size_t count); +static int local_comm_channel; +static int zybo_fifo_rx; +static int zybo_fifo_tx; /* Functions for recording Latencies */ void findTimeDiff(int respID); @@ -121,6 +125,10 @@ pthread_mutex_t quadResponseMutex, cliInputMutex ; unsigned char *commandBuf; int newQuadResponse = 0, newCliInput = 0; +static void sig_handler(int s) { + printf("Caught SIGPIPE from quad fifo..\n"); +} + // Callback to be ran whenever the tracker receives data. // Currently doing much more than it should. It will be slimmed down // in the future. @@ -192,7 +200,13 @@ int main(int argc, char **argv) exit(1); } - printf("zyboSocket = %d\n", zyboSocket); + if (!local_comm_channel) { + printf("zyboSocket = %d\n", zyboSocket); + } else { + /* if we are using fifo's we don't want the quad to be able to shut us down. */ + signal(SIGPIPE, sig_handler); + printf("zybo_fifo_rx = %d\nzybo_fifo_tx = %d\n", zybo_fifo_rx, zybo_fifo_tx); + } if (pthread_mutex_unlock(&quadSocketMutex)) { err(-2, "pthrtead_mutex_unlock (%s:%d):", __FILE__, __LINE__); @@ -211,16 +225,6 @@ int main(int argc, char **argv) strncat(user_specified_log_name, argv[1], strlen(argv[1])); } - char log_file[256]; - create_log_name(log_file, 256); - - printf("Creating log file '%s'...\n",log_file); - quadlog_file = fopen(log_file, "a"); - quadlog_file_open = 1; - - // Tell the quad we are ready to send it vrpn data - sendStartPacket(); - if(!getenv(NOVRPN_ENV)){ printf("Creating VRPN tracker...\n"); // create vrpnTracker instance @@ -279,28 +283,19 @@ int main(int argc, char **argv) } } - ucart_vrpn_tracker_freeInstance(tracker); - safe_close_fd(zyboSocket, &quadSocketMutex); - fclose(quadlog_file); - return 0; -} - -void sendStartPacket() { - uint8_t packet[64]; - struct metadata m; - m.msg_type = BEGINUPDATE_ID; - m.data_len = 0; - m.msg_id = currMessageID++; - ssize_t psize; + ucart_vrpn_tracker_freeInstance(tracker); - if ((psize = EncodePacket(packet, 64, &m, NULL)) < 0) { - warnx("Big problems. sendStartPacket"); - return; + if (!local_comm_channel) { + safe_close_fd(zyboSocket, &quadSocketMutex); + } else { + safe_close_fd(zybo_fifo_rx, &quadSocketMutex); + safe_close_fd(zybo_fifo_tx, &quadSocketMutex); } - writeQuad(packet, psize); - printf("Start Packet sent...\n"); + fclose(quadlog_file); + + return 0; } void sendVrpnPacket(struct ucart_vrpn_TrackerData *info) { @@ -358,22 +353,33 @@ int connectToZybo() { if (getenv(QUAD_COMM_ENV)) { /* Determine if we are using bluetooth or local */ if(strcmp(getenv(QUAD_COMM_ENV), "local") == 0) { - printf("Using Local Socket Settings\n"); + printf("Using Local Fifo Settings\n"); + local_comm_channel = 1; + char * fifo_rx = QUAD_LOCAL_DEFAULT_TX; + char * fifo_tx = QUAD_LOCAL_DEFAULT_RX; - struct sockaddr_un remote; - char str[100]; - - if ((sock = socket(AF_UNIX, SOCK_STREAM, 0)) == -1) { - perror("socket"); - exit(1); + if (getenv(QUAD_LOCAL_RX)) { + fifo_tx = getenv(QUAD_LOCAL_RX); + } + if (getenv(QUAD_LOCAL_TX)) { + fifo_rx = getenv(QUAD_LOCAL_TX); } - remote.sun_family = AF_UNIX; - char * sock_env = getenv(QUAD_LOCAL_SOCKET); - strcpy(remote.sun_path, sock_env ? sock_env : QUAD_DEFAULT_LOCAL_SOCKET); - printf("Attempting to connect to local socket at '%s'. please be patiend.\n", remote.sun_path); - - status = connect(sock, (struct sockaddr *)&remote, sizeof(remote)); + zybo_fifo_tx = open(fifo_tx, O_WRONLY | O_NONBLOCK); + if (zybo_fifo_tx < 0) { + warnx("Opening zybo_fifo_tx..."); + return -1; + } + /* Must use O_RDWR so that there is at least one writer on the fifo + and each subsequent call to select() won't return EOF + */ + zybo_fifo_rx = open(fifo_rx, O_RDWR | O_NONBLOCK); + if (zybo_fifo_rx < 0) { + warnx("Opening zybo_fifo_rx..."); + return -1; + } + status = 0; + sock = zybo_fifo_rx; } else if (strcmp(getenv(QUAD_COMM_ENV), "bluetooth") == 0) { printf("Using BT Settings\n"); struct sockaddr_rc addr; @@ -479,7 +485,13 @@ static ssize_t writeQuad(const uint8_t * buf, size_t count) { if (pthread_mutex_lock(&quadSocketMutex)) { err(-2, "pthrtead_mutex_lock (%s:%d):", __FILE__, __LINE__); } - retval = write(zyboSocket, buf, count); + + if (local_comm_channel) { + retval = write(zybo_fifo_tx, buf, count); + } else { + retval = write(zyboSocket, buf, count); + } + if (pthread_mutex_unlock(&quadSocketMutex)) { err(-2, "pthrtead_mutex_unlock (%s:%d):", __FILE__, __LINE__); } @@ -495,7 +507,13 @@ static ssize_t readQuad(char * buf, size_t count) { if (pthread_mutex_lock(&quadSocketMutex)) { err(-2, "pthrtead_mutex_lock (%s:%d):", __FILE__, __LINE__); } - retval = read(zyboSocket, buf, count); + + if (local_comm_channel) { + retval = read(zybo_fifo_rx, buf, count); + } else { + retval = read(zyboSocket, buf, count); + } + if (pthread_mutex_unlock(&quadSocketMutex)) { err(-2, "pthrtead_mutex_unlock (%s:%d):", __FILE__, __LINE__); } @@ -751,6 +769,7 @@ static void client_recv(int fd) { int retval = writeQuad(packet, psize); // printf("sent %d bytes\n", retval); + free(data); } @@ -764,6 +783,7 @@ static void client_recv(int fd) { static void quad_recv() { static unsigned char respBuf[CMD_MAX_LENGTH]; static size_t respBufLen; + static int receiving_logs; struct metadata m; uint8_t data[CMD_MAX_LENGTH]; @@ -786,7 +806,8 @@ static void quad_recv() { // } // printf("'\n"); - while(respBufLen){ + + while(respBufLen) { datalen = DecodePacket(&m, data, CMD_MAX_LENGTH, respBuf, respBufLen); if (datalen == -1) { warnx("No start Byte"); @@ -824,6 +845,10 @@ static void quad_recv() { respBufLen -= packetlen; switch (m.msg_type) { + case DEBUG_ID: + /* in case of debug. Quad send null terminated string in data */ + printf(" (Quad) : %s\n", data); + break; case LOG_ID: if (!quadlog_file_open) { char log_file[256]; @@ -832,7 +857,13 @@ static void quad_recv() { quadlog_file = fopen(log_file, "a"); quadlog_file_open = 1; } - //printf("(Quad) : Log found\n"); + if (!receiving_logs) { + printf("(Quad) : Log found\n"); + receiving_logs = 1; + } else { + printf("."); + fflush(0); + } fwrite((char *) data, sizeof(char), m.data_len, quadlog_file); break; case RESPPARAM_ID: @@ -847,19 +878,24 @@ static void quad_recv() { fclose(quadlog_file); quadlog_file_open = 0; } - printf("(Quad) : Log End found\n"); + printf("\n(Quad) : Log End found\n"); + receiving_logs = 0; break; default: printf("(Backend): message type %d ignored from quad\n", m.msg_type); break; } - } + } } static void handleResponse(struct metadata *m, uint8_t * data) { - ssize_t result; + ssize_t result = 0; char *buffer = malloc(sizeof(*buffer) * 128); + if (!buffer) { + warnx("failed immediatly"); + return; + } switch (m->msg_type) { case RESPPARAM_ID: @@ -872,20 +908,23 @@ static void handleResponse(struct metadata *m, uint8_t * data) result = DecodeResponseOutput(buffer, 128, m, data); break; case RESPNODES_ID: - result = DecodeResponseGetNodes(buffer, 128, m, data); + result = DecodeResponseGetNodes(&buffer, 128, m, data); break; case RESPADDNODE_ID: result = DecodeResponseAddNode(buffer, 128, m, data); break; default: - result = -1; + result = -2; break; } - if (result < 0) { + if (result == -2) { warnx("DecodeResponse error"); free(buffer); return; + } else if (result < 0) { + warnx("DecodeResponse error"); + return; } // printf("msg to client = '%s'\n", buffer); @@ -942,7 +981,7 @@ void findTimeDiff(int respID) { char * create_log_name(char * buffer, size_t max) { static const char * prefix = "logs"; static size_t num_logs = 0; - static const char * format_string = "%Y-%m-%e_%-l:%M"; + static const char * format_string = "%F_%-l:%M"; time_t curr_time; char c_time_string[256]; diff --git a/groundStation/src/backend/callbacks.c b/groundStation/src/backend/callbacks.c deleted file mode 100644 index 875167b483adc933f8dfcc57507a84a0b6c936ae..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/callbacks.c +++ /dev/null @@ -1,3 +0,0 @@ -#include "commands.h" - -/* New stuff - this is nice and clean */ diff --git a/groundStation/src/backend/callbacks.h b/groundStation/src/backend/callbacks.h deleted file mode 100644 index cc5fd8cabe8e5655b318df854b0731646076c4d2..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/callbacks.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef __CALLBACKS_H -#define __CALLBACKS_H - -/* Grab some stupid stuff from legacy code */ -#include "type_def.h" - -/* Make commands.c happy */ -typedef void (command_cb)(void); - -#endif /* __CALLBACKS_H */ diff --git a/groundStation/src/backend/config.h b/groundStation/src/backend/config.h index 9306bd65ecf4ca80e60fb118a942e8fff00131d1..4236b1328142c9583dee075e92380f499412995e 100644 --- a/groundStation/src/backend/config.h +++ b/groundStation/src/backend/config.h @@ -13,8 +13,12 @@ // backend with sudo elevation and with the --preserve-env flag or -E #define QUAD_COMM_ENV "UCART_COMM_CHANNEL" -#define QUAD_DEFAULT_LOCAL_SOCKET "./virtquad.socket" -#define QUAD_LOCAL_SOCKET "UCART_LOCAL_SOCKET" +#define QUAD_LOCAL_RX "UCART_LOCAL_RX" +#define QUAD_LOCAL_TX "UCART_LOCAL_TX" +#define QUAD_LOCAL_DEFAULT_RX "../quad/bin/virt-quad-fifos/uart-rx" +#define QUAD_LOCAL_DEFAULT_TX "../quad/bin/virt-quad-fifos/uart-tx" + + #define QUAD_IP_ENV "UCART_QUAD_IP" #define QUAD_IP_DEFAULT "192.168.1.1" #define QUAD_PORT_ENV "UCART_QUAD_PORT" diff --git a/groundStation/src/backend/nodes.c b/groundStation/src/backend/nodes.c index 695f58a00a0c67d0cdbe86db9a88c544bb6c67af..ec428f2dea92db1b9254053c140a0ad53b9a62b7 100644 --- a/groundStation/src/backend/nodes.c +++ b/groundStation/src/backend/nodes.c @@ -51,7 +51,11 @@ ssize_t EncodeAddNode( int16_t type; char name[512]; - sscanf(msg, "addnode %" SCNd16 "%s\n", &type, name); + memset(name, 0, 512); + + sscanf(msg, "addnode %" SCNd16 " %512c", &type, name); + + printf("found name '%s'\n", name); data[AN_TYPE_ID_L] = LSByte16(type); data[AN_TYPE_ID_H] = MSByte16(type); @@ -73,8 +77,10 @@ static int resizeMsg(char **msg_ptr, int *curr_max, int check_val) { /* resize the msg if necessary */ if (*curr_max < check_val) { *curr_max = *curr_max * 4; + char *old_ptr = *msg_ptr; *msg_ptr = realloc(*msg_ptr, sizeof(**msg_ptr) * *curr_max); if (!msg_ptr) { + *msg_ptr = old_ptr; return -1; } } @@ -85,7 +91,7 @@ static int resizeMsg(char **msg_ptr, int *curr_max, int check_val) { * Returns bytes written to msg, -1 on failure. */ int DecodeResponseGetNodes( - char * msg, /* Out */ + char ** msg, /* Out */ size_t max_len, /* msg buffer max size */ const struct metadata *m, /* In */ const uint8_t * data) /* In */ @@ -100,8 +106,8 @@ int DecodeResponseGetNodes( uint16_t num_nodes = BytesTo16(data[RESP_GN_NUM_NODES_L], data[RESP_GN_NUM_NODES_H]); - if (resizeMsg(&msg, (int *)&max_len, (m->data_len *2)) == -1) { - return -1; + if (resizeMsg(msg, (int *)&max_len, (m->data_len *2)) == -1) { + return -2; } int16_t val; @@ -109,29 +115,28 @@ int DecodeResponseGetNodes( size_t i; int msg_len = 0, msg_offset = 0, data_offset = RESP_GN_MIN_DATA_SIZE; - sprintf(msg, "getnodes %hu %n", num_nodes, &msg_offset); + sprintf(*msg, "getnodes %hu %n", num_nodes, &msg_offset); msg_len += msg_offset; - for(i = 0; i < num_nodes * 3; ++i) { if (i < num_nodes * 2) { val = BytesTo16(data[data_offset], data[data_offset+1]); data_offset += 2; - sprintf(&msg[msg_len], "%" PRId16 " %n", val, &msg_offset); + sprintf(&(*msg)[msg_len], "%" PRId16 " %n", val, &msg_offset); } else { strncpy(name, (char *) (data + data_offset), 512); data_offset += strlen(name) + 1; - sprintf(&msg[msg_len], "'%s' %n", name, &msg_offset); + sprintf(&(*msg)[msg_len], "'%s' %n", name, &msg_offset); } msg_len += msg_offset; - if (resizeMsg(&msg, (int *)&max_len, msg_len + (msg_offset *2)) == -1) { - return -1; + if (resizeMsg(msg, (int *)&max_len, msg_len + (msg_offset *2)) == -1) { + return -2; } } - strcat(&msg[msg_len], "\n"); - return strlen(msg); + strcat(&(*msg)[msg_len], "\n"); + return strlen(*msg); } enum ResponseAddnodeData { diff --git a/groundStation/src/backend/nodes.h b/groundStation/src/backend/nodes.h index 18f57c9a35419e483253da94b3e69e2d7c657fec..3ffc1bc7084a2c15c521d14ac83ac516b48e1c3c 100644 --- a/groundStation/src/backend/nodes.h +++ b/groundStation/src/backend/nodes.h @@ -29,7 +29,7 @@ ssize_t EncodeAddNode( * Returns bytes written to msg, -1 on failure. */ int DecodeResponseGetNodes( - char * msg, /* Out */ + char ** msg, /* Out */ size_t max_len, /* msg buffer max size */ const struct metadata *m, /* In */ const uint8_t * data); /* In */ diff --git a/groundStation/src/backend/packet.c b/groundStation/src/backend/packet.c index 7ddbb536321603a819f7af2c6195636e8a1aba52..abcb42490b177873964cf0715270a87b7a6087d0 100644 --- a/groundStation/src/backend/packet.c +++ b/groundStation/src/backend/packet.c @@ -14,7 +14,7 @@ ssize_t EncodePacket( const struct metadata * m, /* Metadata to encode */ const uint8_t * data) /* Data to encode */ { - if (packet_size < (HDR_SIZE + CSUM_SIZE + m->data_len)) { + if (packet_size < (size_t)(HDR_SIZE + CSUM_SIZE + m->data_len)) { return -1; } @@ -58,7 +58,7 @@ ssize_t DecodePacket( m->msg_id = BytesTo16(packet[ID_L], packet[ID_H]); m->data_len = BytesTo16(packet[DLEN_L], packet[DLEN_H]); - if (packet_size < (HDR_SIZE + CSUM_SIZE + m->data_len)) { + if (packet_size < (size_t)(HDR_SIZE + CSUM_SIZE + m->data_len)) { return -3; } diff --git a/groundStation/src/backend/packet.h b/groundStation/src/backend/packet.h index 87f8c5c7e73ef23bbd9bbc7befb3d5c897ad3b57..316432797b9fe820e9cb8603f022e45411e63af4 100644 --- a/groundStation/src/backend/packet.h +++ b/groundStation/src/backend/packet.h @@ -4,6 +4,8 @@ #include <stdint.h> #include <sys/types.h> +#include "commands.h" + enum PacketHeader { BEGIN, MTYPE_L, @@ -19,11 +21,6 @@ enum ChecksumFormat { CSUM_L, CSUM_SIZE }; -struct metadata { - int msg_type; - int msg_id; - size_t data_len; -}; /* Combine metadata and data to form a wire-sendable packet. * Returns the size of the encoded packet diff --git a/groundStation/src/backend/type_def.h b/groundStation/src/backend/type_def.h deleted file mode 100644 index 27b5d192e5538c326668b45785d0be62028e0ee8..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/type_def.h +++ /dev/null @@ -1,360 +0,0 @@ -/* - * struct_def.h - * - * Created on: Mar 2, 2016 - * Author: ucart - */ - -#ifndef __TYPE_DEF_H -#define __TYPE_DEF_H - -/** - * @brief - * The modes for autonomous and manual flight. - * - */ -enum flight_mode{ - AUTO_FLIGHT_MODE, - MANUAL_FLIGHT_MODE -}; - -//---------------------------------------------------------------------------------------------- -// index|| 0 | 1 | 2 | 3 & 4 | 5 & 6 | 7+ | end | -//---------------------------------------------------------------------------------------------| -// msg param|| beg char | msg type | msg subtype | msg id | data len (bytes) | data | checksum | -//-------------------------------------------------------------------------------------------- | -// bytes|| 1 | 1 | 1 | 2 | 2 | var | 1 | -//---------------------------------------------------------------------------------------------- -typedef struct { - char begin_char; - int msg_type; - int msg_id; - int data_len; -} metadata_t; - - -// String builder data type -typedef struct stringBuilder_s { - char* buf; - int length; - int capacity; - int maxCapacity; - - // Methods - int (*addStr)(struct stringBuilder_s*, char*); - int (*addStrAt)(struct stringBuilder_s*, char*, int); - int (*addChar)(struct stringBuilder_s*, char); - int (*addCharAt)(struct stringBuilder_s*, char, int); - int (*removeCharAt)(struct stringBuilder_s*, int); - void (*clear)(struct stringBuilder_s*); -} stringBuilder_t; - -typedef struct { - char** tokens; - int numTokens; -} tokenList_t; - -typedef struct commands{ - int pitch, roll, yaw, throttle; -}commands; - -typedef struct raw{ - int x,y,z; -}raw; -typedef struct PID_Consts{ - float P, I, D; -}PID_Consts; - -//Camera system info -typedef struct { - int packetId; - - double y_pos; - double x_pos; - double alt_pos; - - double yaw; - double roll; - double pitch; -} quadPosition_t; - -typedef struct { - float yaw; - float roll; - float pitch; - float throttle; -} quadTrims_t; - -//Gyro, accelerometer, and magnetometer data structure -//Used for reading an instance of the sensor data -typedef struct { - - // GYRO - //Xint16 raw_gyro_x, raw_gyro_y, raw_gyro_z; - - float gyro_xVel_p; // In degrees per second - float gyro_yVel_q; - float gyro_zVel_r; - - // ACCELEROMETER - //Xint16 raw_accel_x, raw_accel_y, raw_accel_z; - - float accel_x; //In g - float accel_y; - float accel_z; - - float accel_roll; - float accel_pitch; - - - // MAG - //Xint16 raw_mag_x, raw_mag_y, raw_mag_z; - - float heading; // In degrees - - float mag_x; //Magnetic north: ~50 uT - float mag_y; - float mag_z; - - - -}gam_t; - -typedef struct PID_t { - double current_point; // Current value of the system - double setpoint; // Desired value of the system - float Kp; // Proportional constant - float Ki; // Integral constant - float Kd; // Derivative constant - double prev_error; // Previous error - double acc_error; // Accumulated error - double pid_correction; // Correction factor computed by the PID - float dt; // sample period -} PID_t; - -typedef struct PID_values{ - float P; // The P component contribution to the correction output - float I; // The I component contribution to the correction output - float D; // The D component contribution to the correction output - float error; // the error of this PID calculation - float change_in_error; // error change from the previous calc. to this one - float pid_correction; // the correction output (P + I + D) -} PID_values; - -///////// MAIN MODULAR STRUCTS -/** - * @brief - * Holds the data inputed by the user - * - */ -typedef struct user_input_t { - int rc_commands[6]; // Commands from the RC transmitter - - -// float cam_x_pos; // Current x position from the camera system -// float cam_y_pos; // Current y position from the camera system -// float cam_z_pos; // Current z position from the camera system -// float cam_roll; // Current roll angle from the camera system -// float cam_pitch; // Current pitch angle from the camera system -// float cam_yaw; // Current yaw angle from the camera system - - float yaw_manual_setpoint; - float roll_angle_manual_setpoint; - float pitch_angle_manual_setpoint; - - int hasPacket; - stringBuilder_t * sb; -} user_input_t; - -/** - * @brief - * Holds the log data to be sent to the ground station. It may hold the - * timestamp of when a sensor's data was obtained. - * - */ -typedef struct log_t { - // Time - float time_stamp; - float time_slice; - - // Id - int packetId; - - gam_t gam; // Raw and calculated gyro, accel, and mag values are all in gam_t - float phi_dot, theta_dot, psi_dot; // gimbal equation values - - quadPosition_t currentQuadPosition; - - float roll_angle_filtered, pitch_angle_filtered; - float lidar_altitude; - - float pid_P_component, pid_I_component, pid_D_component; // use these generically for any PID that you are testing - - // PID coefficients and errors - PID_t local_x_PID, local_y_PID, altitude_PID; - PID_t angle_yaw_PID, angle_roll_PID, angle_pitch_PID; - PID_t ang_vel_yaw_PID, ang_vel_roll_PID, ang_vel_pitch_PID; - - PID_values local_x_PID_values, local_y_PID_values, altitude_PID_values; - PID_values angle_yaw_PID_values, angle_roll_PID_values, angle_pitch_PID_values; - PID_values ang_vel_yaw_PID_values, ang_vel_roll_PID_values, ang_vel_pitch_PID_values; - - // RC commands - commands commands; - - //trimmed values - quadTrims_t trims; - - int motors[4]; - -} log_t; - -/** - * @brief - * Holds the raw data from the sensors and the timestamp if available - * - */ -typedef struct raw_sensor { - int acc_x; // accelerometer x data - int acc_x_t; // time of accelerometer x data - - int acc_y; // accelerometer y data - int acc_y_t; // time of accelerometer y data - - int acc_z; // accelerometer z data - int acc_z_t; // time of accelerometer z data - - - int gyr_x; // gyroscope x data - int gyr_x_t; // time of gyroscope x data - - int gyr_y; // gyroscope y data - int gyr_y_t; // time of gyroscope y data - - int gyr_z; // gyroscope z data - int gyr_z_t; // time of gyroscope z data - - int ldr_z; //lidar z data (altitude) - int ldr_z_t; //time of lidar z data - - gam_t gam; - - // Structures to hold the current quad position & orientation - quadPosition_t currentQuadPosition; - -} raw_sensor_t; - -/** - * @brief - * Holds the processed data from the sensors and the timestamp if available - * - */ -typedef struct sensor { - int acc_x; // accelerometer x data - int acc_x_t; // time of accelerometer x data - - int acc_y; // accelerometer y data - int acc_y_t; // time of accelerometer y data - - int acc_z; // accelerometer z data - int acc_z_t; // time of accelerometer z data - - - int gyr_x; // gyroscope x data - int gyr_x_t; // time of gyroscope x data - - int gyr_y; // gyroscope y data - int gyr_y_t; // time of gyroscope y data - - int gyr_z; // gyroscope z data - int gyr_z_t; // time of gyroscope z data - - int ldr_z; //lidar z data (altitude) - int ldr_z_t; //time of lidar z data - - float pitch_angle_filtered; - float roll_angle_filtered; - float lidar_altitude; - - float phi_dot, theta_dot, psi_dot; - - // Structures to hold the current quad position & orientation - quadPosition_t currentQuadPosition; - quadTrims_t trims; - -} sensor_t; - -/** - * @brief - * Holds the setpoints to be used in the controller - * - */ -typedef struct setpoint_t { - quadPosition_t desiredQuadPosition; -} setpoint_t; - -/** - * @brief - * Holds the parameters that are specific to whatever type of - * control algorithm is being used - * - */ -typedef struct parameter_t { - PID_t roll_angle_pid, roll_ang_vel_pid; - PID_t pitch_angle_pid, pitch_ang_vel_pid; - PID_t yaw_ang_vel_pid; - PID_t local_x_pid; - PID_t local_y_pid; - PID_t yaw_angle_pid; - PID_t alt_pid; -} parameter_t; - -/** - * @brief - * Holds user defined data for the controller - * - */ -typedef struct user_defined_t { - int flight_mode; - int engaging_auto; -} user_defined_t; - -/** - * @brief - * Holds the raw actuator values before processing - * - */ -typedef struct raw_actuator_t { - - int controller_corrected_motor_commands[6]; - -} raw_actuator_t; - -/** - * @brief - * Holds processed commands to go to the actuators - * - */ -typedef struct actuator_command_t { - int pwms[4]; -} actuator_command_t; - -/** - * @brief - * Structures to be used throughout - */ -typedef struct { - user_input_t user_input_struct; - log_t log_struct; - raw_sensor_t raw_sensor_struct; - sensor_t sensor_struct; - setpoint_t setpoint_struct; - parameter_t parameter_struct; - user_defined_t user_defined_struct; - raw_actuator_t raw_actuator_struct; - actuator_command_t actuator_command_struct; -}modular_structs_t; - -//////// END MAIN MODULAR STRUCTS - -#endif /* __TYPE_DEF_H */ diff --git a/groundStation/src/cli/cli.c b/groundStation/src/cli/cli.c index ebde95590a1250cb280f6e8329a81d465d8ecd65..139534a4742e4b68b388cd9240d001c257c7fb77 100644 --- a/groundStation/src/cli/cli.c +++ b/groundStation/src/cli/cli.c @@ -3,6 +3,7 @@ #include <err.h> #include <libgen.h> #include <getopt.h> +#include <stdlib.h> #include "cli.h" @@ -15,6 +16,7 @@ int main(int argc, char **argv) struct backend_conn *conn; int needCliHelp = 0, needCommandHelp = 0; + setenv("POSIXLY_CORRECT", "1",1); // Determine if the cli was called using a symlink command = basename(argv[0]); for(i = 0; i < MAX_COMMANDS; ++i) { @@ -154,13 +156,11 @@ int isNumber(char *number) { int convert_to_id(struct backend_conn * conn, char **argv, struct convert_data * convert_data, int conversion_requirement) { /* variables used to search for id values */ - size_t num_nodes = 0, i; - struct frontend_node_data* search_data; + size_t num_nodes = 0, i = 0; + struct frontend_node_data* search_data = NULL; int search_1 = 0, search_2 = 0; const struct graph_node_type * node_definition; - - if (!isNumber(argv[1])) { search_1 = 1; } else { @@ -177,8 +177,10 @@ int convert_to_id(struct backend_conn * conn, char **argv, struct convert_data * return 0; } - search_data = malloc(sizeof((*search_data)) * num_nodes); - + /** + * node_data must be NULL, + * num_nodes must equal zero. + */ if (frontend_getnodes(conn, &search_data, &num_nodes)) { return 1; } @@ -229,9 +231,6 @@ int convert_to_id(struct backend_conn * conn, char **argv, struct convert_data * } } } - for(i = 0; i < num_nodes; ++i) { - free(search_data[i].name); - } - free(search_data); + frontend_free_node_data(search_data, num_nodes); return search_2; } \ No newline at end of file diff --git a/groundStation/src/cli/cli_nodes.c b/groundStation/src/cli/cli_nodes.c index 281ee6fb60dfd66b29c60515748a7fc6c908a344..892be2e3da46d8a3b9642680baf733f9f2e67737 100644 --- a/groundStation/src/cli/cli_nodes.c +++ b/groundStation/src/cli/cli_nodes.c @@ -11,7 +11,7 @@ int cli_getnodes(struct backend_conn * conn, int argc, char ** argv) { size_t num_nodes = 0; - struct frontend_node_data * node_data; + struct frontend_node_data * node_data = NULL; int needHelp = 0; @@ -30,53 +30,50 @@ int cli_getnodes(struct backend_conn * conn, int argc, char ** argv) { return 1; } - node_data = malloc(sizeof(*node_data)); - + /** + * node_data must be NULL, + * num_nodes must equal zero. + */ if (frontend_getnodes(conn, &node_data, &num_nodes)) { free(node_data); return 1; } - printf("--------------------------------------------------------------------------------------------------------------\n"); + printf("----------------------------------------------------------------------------------------------------\n"); printf("The following %lu Nodes have been found:\n", num_nodes); - printf("--------------------------------------------------------------------------------------------------------------\n"); - printf("\tBLOCK\t\tTYPE\t\tNAME\t\tINPUTS\t\tPARAMS\t\tOUTPUTS\n"); - printf("--------------------------------------------------------------------------------------------------------------\n"); + printf("----------------------------------------------------------------------------------------------------\n"); + printf(" BLOCK\tTYPE\tNAME\t\tINPUTS\t\tPARAMS\t\tOUTPUTS\n"); + printf("----------------------------------------------------------------------------------------------------\n"); for(i = 0; i < num_nodes; ++i) { - printf("\t%3d\t\t%3d\t\t%s\t", node_data[i].block, node_data[i].type, node_data[i].name); + printf(" %3d\t%3d\t%s\t", node_data[i].block, node_data[i].type, node_data[i].name); const struct graph_node_type * node_definition = blockDefs[node_data[i].type]; printf(" {"); - for(n = 0; n < (size_t)node_definition->n_inputs; ++n) { printf(" %-5s ", node_definition->input_names[n]); } printf("} "); printf(" {"); - for(n = 0; n < (size_t)node_definition->n_params; ++n) { printf(" %s ", node_definition->param_names[n]); } printf("} "); - + printf(" {"); - for(n = 0; n < (size_t)node_definition->n_outputs; ++n) { printf(" %s ", node_definition->output_names[n]); } printf("}\n"); - - - free(node_data[i].name); } - free(node_data); + frontend_free_node_data(node_data, num_nodes); return 0; } int cli_addnode(struct backend_conn * conn, int argc, char ** argv) { struct frontend_node_data node_data; + int needHelp = 0; if ((needHelp = help_check(argc, argv))) { @@ -91,8 +88,12 @@ int cli_addnode(struct backend_conn * conn, int argc, char ** argv) { return 1; } + if ((node_data.name = (char *)malloc(strlen(argv[2]))) == NULL) { + return 1; + } + node_data.type = atoi(argv[1]); - strncpy(node_data.name, argv[2], 512/* this value matches the max space of name */ ); + strncpy(node_data.name, argv[2], strlen(argv[2])); if (frontend_addnode(conn, &node_data)) { return 1; diff --git a/quad/Makefile b/quad/Makefile index d04ffe0e3d8af5a9842809be690f7ab85d30e134..f67155208f9f817476423cf8744f8764f37c37b4 100644 --- a/quad/Makefile +++ b/quad/Makefile @@ -6,7 +6,7 @@ WS = $(CURDIR)/xsdk_workspace BOOT = $(OUTDIR)/BOOT.bin -.PHONY: all libs zybo boot test clean deep-clean +.PHONY: all libs zybo boot run-virt-quad test clean deep-clean all: libs bins @@ -20,16 +20,27 @@ libs: bins: $(MAKE) -C src/virt_quad + $(MAKE) -C src/gen_diagram zybo: bash scripts/build_zybo.sh +# For creating an image of the control network. +diagram: + $(MAKE) -C src/gen_diagram diagram + boot: $(BOOT) -test: +run-virt-quad: + $(MAKE) -C src/virt_quad run + +test: all $(MAKE) -C src/queue test $(MAKE) -C src/computation_graph test $(MAKE) -C src/quad_app test + ruby scripts/tests/test_safety_checks.rb + ruby scripts/tests/test_unix_uart.rb + ruby scripts/tests/run_virtual_test_flight.rb clean: rm -rf $(INCDIR) $(LIBDIR) $(OUTDIR) $(EXEDIR) @@ -42,10 +53,9 @@ deep-clean: $(MAKE) -C src/graph_blocks clean $(MAKE) -C src/commands clean $(MAKE) -C src/quad_app clean - bash scripts/clean_xsdk_workspace.sh $(OUTDIR): mkdir $(OUTDIR) $(BOOT): zybo | $(OUTDIR) - bash scripts/create_zybo_boot.sh + bash scripts/xsdk/create_zybo_boot.sh diff --git a/quad/README.md b/quad/README.md index 8f857b03bcd9bba8e4e76f3617313d0ad7dd2b2d..5bc803bc5cf3ea19c816e022a2617275081f827a 100644 --- a/quad/README.md +++ b/quad/README.md @@ -1,26 +1,29 @@ # Quadcopter -The quad/ directory contains all code that programs the quadcopter. This +The `quad/` directory contains all code that programs the quadcopter. This includes any C libraries we have written, any HDL to program the Zybo on the quad, and the XSDK main project that runs on the Zybo. -The main quad application is written as a library, and located at: -``` -src/quad_app/quad_app.c -``` +## Documents +[Zybo Pinout Assignments](doc/zybo_pinout_assignments.md) +[How to use Xilinx software tools](doc/how_to_use_xilinx_tools.pdf) -The main XSDK project that actually runs on the Zybo is located at: -``` -xsdk_workspace/modular_quad_pid/main.c -``` +## Software Instructions -## Building +The main quad application is written as a library, and located at +`src/quad_app/` ("main" function in quad_app.c). + +The main XSDK project that actually runs on the Zybo is located at +`xsdk_workspace/real_quad/` + +We also have a complemetary "virtual quad" to ease testing located at +`src/virt_quad/` -### Libraries +## Building To build the libraries: ``` -make libs +make ``` You can also build each library individually inside their respective project @@ -29,38 +32,34 @@ directories: cd src/<project> && make ``` -### XSDK Project - -To build the XSDK project that runs on the Zybo (only works on co3050): +To build the XSDK project, use the XSDK IDE. Source the proper XSDK files, and +then start up the XSDK IDE. Be sure to select the `xsdk_workspace` directory +in the quad directory as your "workspace": ``` -make zybo +source /opt/Xilinx/14.7/ISE_DS/settings64.sh +xsdk & ``` -To build the Zybo boot image for the SD card (only works on co3050): -``` -make boot -``` - -Disclaimer: The make boot target currently does not work - ## Testing -### Libraries +_Write tests! It makes automating things so much easier._ -We try to write unit tests for the libraries we've written, since they are -not tied to the Zybo platform and are able to be run in our CI environment. +Run the unit and functional tests: ``` make test ``` -You can also run the test for specific library inside its respective project +You can also run the test for a specific library inside its respective project directory: ``` cd src/<project> && make test ``` -### XSDK Project +### Manually testing the hardware interface + +Of course, we cannot run our automated tests on code that needs the Zybo. But +we have manual tests that you can use to test each specific driver in the +hardware interface. -The XSDK project implements the hardware interfaces used in the quad app. -There are tests can be executed from the main function in that XSDK project. -These tests essentially test each hardware interface. +Look in `xsdk_workspace/real_quad/src/hw_impl_zybo_tests.c` for instructions. +Ideally, you would run these tests from the XSDK IDE. diff --git a/quad/doc/.gitkeep b/quad/doc/.gitkeep new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/quad/doc/how_to_use_xilinx_tools.pdf b/quad/doc/how_to_use_xilinx_tools.pdf new file mode 100644 index 0000000000000000000000000000000000000000..c2ab059fc874a1a936cccf5dc169a7d2cad23810 Binary files /dev/null and b/quad/doc/how_to_use_xilinx_tools.pdf differ diff --git a/quad/doc/zybo_pinout_assignments.md b/quad/doc/zybo_pinout_assignments.md new file mode 100644 index 0000000000000000000000000000000000000000..05c3de7e849595b35d19101580e31fed3ad2b52f --- /dev/null +++ b/quad/doc/zybo_pinout_assignments.md @@ -0,0 +1,65 @@ +# Zybo Pinout Assignments + +The Zybo board has 6 PMOD Connectors. We use these for most quad I/O. + + + +## PMOD Assignment Table +``` +Zybo PMOD Pin : Zync Pin : Xilinx Pin Name : Our Assignment + +JF1 : MIO-13 : N/A : unused +JF2 : MIO-10 : N/A : I2C0 SCL +JF3 : MIO-11 : N/A : I2C0 SDA +JF4 : MIO-12 : N/A : unused +JF7 : MIO-0 : N/A : unused +JF8 : MIO-9 : N/A : unused +JF9 : MIO-14 : N/A : unused +JF10 : MIO-15 : N/A : unused + +JE1 : V12 : IO_L4P_T0_34 : pwm_recorder_0 +JE2 : W16 : IO_L18N_T2_34 : pwm_recorder_1 +JE3 : J15 : IO_25_35 : pwm_recorder_2 +JE4 : H15 : IO_L19P_T3_35 : pwm_recorder_3 +JE7 : V13 : IO_L3N_T0_DQS_34 : pwm_signal_out_wkillswitch_0 +JE8 : U17 : IO_L9N_T1_DQS_34 : pwm_signal_out_wkillswitch_1 +JE9 : T17 : IO_L20P_T3_34 : pwm_signal_out_wkillswitch_2 +JE10 : Y17 : IO_L7N_T1_34 : pwm_signal_out_wkillswitch_3 + +JD1 : T14 : IO_L5P_T0_34 : unused +JD2 : T15 : IO_L5N_T0_34 : unused +JD3 : P14 : IO_L6P_T0_34 : unused +JD4 : R14 : IO_L6N_T0_VREF_34 : unused +JD7 : U14 : IO_L11P_T1_SRCC_34 : pwm_recorder_4 +JD8 : U15 : IO_L11N_T1_SRCC_34 : pwm_recorder_5 +JD9 : V17 : IO_L21P_T3_DQS_34 : unused +JD10 : V18 : IO_L21N_T3_DQS_34 : unused + +JC1 : V15 : IO_L10P_T1_34 : unused +JC2 : W15 : IO_L10N_T1_34 : processing_system7_0_UART0_TX_pin +JC3 : T11 : IO_L1P_T0_34 : processing_system7_0_UART0_RX_pin +JC4 : T10 : IO_L1N_T0_34 : unused +JC7 : W14 : IO_L8P_T1_34 : unused +JC8 : Y14 : IO_L8N_T1_34 : unused +JC9 : T12 : IO_L2P_T0_34 : unused +JC10 : U12 : IO_L2N_T0_34 : unused + +JB1 : T20 : IO_L15P_T2_DQS_34 : unused +JB2 : U20 : IO_L15N_T2_DQS_34 : unused +JB3 : V20 : IO_L16P_T2_34 : unused +JB4 : W20 : IO_L16N_T2_34 : unused +JB7 : Y18 : IO_L17P_T2_34 : unused +JB8 : Y19 : IO_L17N_T2_34 : unused +JB9 : W18 : IO_L22P_T3_34 : unused +JB10 : W19 : IO_L22N_T3_34 : unused + +JA1 : N15 : IO_L21P_T3_DQS_AD14P_35 : unused +JA2 : L14 : IO_L22P_T3_AD7P_35 : unused +JA3 : K16 : IO_L24P_T3_AD15P_35 : unused +JA4 : K14 : IO_L20P_T3_AD6P_35 : unused +JA7 : N16 : IO_L21N_T3_DQS_AD14N_35 : unused +JA8 : L15 : IO_L22N_T3_AD7N_35 : unused +JA9 : L16 : IO_L16P_T2_34 : unused +JA10 : L14 : IO_L14P_T2_AD4P_SRCC_35 : unused + +``` \ No newline at end of file diff --git a/quad/executable.mk b/quad/executable.mk index d17244a837c5c785fcf53ffb3f547d110d0be88a..0f5f6435227675076c41ae9cdafe964c1bdec8f6 100644 --- a/quad/executable.mk +++ b/quad/executable.mk @@ -12,6 +12,8 @@ OBJECTS = $(patsubst %.c, $(OBJDIR)/%.o, $(SOURCES)) TARGET = $(EXEDIR)/$(NAME) +CLEANUP = $(TARGET) $(OBJDIR) + .PHONY: default run clean ################ @@ -24,7 +26,7 @@ run: $(TARGET) $(EXEDIR)/$(NAME) clean: - rm -rf $(TARGET) $(OBJDIR) + rm -rf $(CLEANUP) #################### ## Internal Targets diff --git a/quad/scripts/#send_raw.py# b/quad/scripts/#send_raw.py# deleted file mode 100755 index f2312f463a95cf94c3408b01e78fe3986e0602fe..0000000000000000000000000000000000000000 --- a/quad/scripts/#send_raw.py# +++ /dev/null @@ -1,12 +0,0 @@ -#!/ - -import sys - -print(sys.version_info) -import serial - -if __name__ == '__main__': - data = bytes.fromhex('be040002001c0002000000d80471be5732703f9d16093f8bf7a03d0586ab3d006d3a40c1') - - with serial.Serial('/dev/ttyUSB0', 115200) as ser: - ser.write(data) diff --git a/quad/scripts/__pycache__/uart_stress_tests.cpython-36.pyc b/quad/scripts/__pycache__/uart_stress_tests.cpython-36.pyc deleted file mode 100644 index 4b92a40fddc351f17e205b35da850c41744a373c..0000000000000000000000000000000000000000 Binary files a/quad/scripts/__pycache__/uart_stress_tests.cpython-36.pyc and /dev/null differ diff --git a/quad/scripts/send_raw.py b/quad/scripts/send_raw.py deleted file mode 100755 index 32cd0efb13591ea7018be0f7947ad143474445ef..0000000000000000000000000000000000000000 --- a/quad/scripts/send_raw.py +++ /dev/null @@ -1,12 +0,0 @@ -#!/usr/bin/python - -import sys - -print(sys.version_info) -import serial - -if __name__ == '__main__': - data = bytes.fromhex('be040002001c0002000000d80471be5732703f9d16093f8bf7a03d0586ab3d006d3a40c1') - - with serial.Serial('/dev/ttyUSB0', 921600) as ser: - ser.write(data) diff --git a/quad/scripts/send_raw.sh b/quad/scripts/send_raw.sh deleted file mode 100755 index a92551e78fbe4aa161d5a745f619ef90d8d3e723..0000000000000000000000000000000000000000 --- a/quad/scripts/send_raw.sh +++ /dev/null @@ -1,10 +0,0 @@ -#!/bin/bash - -# Use the usb port on this machine that you are using for UART -USB_UART=ttyUSB0 - -MSG="\xbe\x04\x00\x02\x00\x1c\x00\x02\x00\x00\x00\xd8\x04\x71\xbe\x57\x32\x70\x3f\x9d\x16\x09\x3f\x8b\xf7\xa0\x3d\x05\x86\xab\x3d\x00\x6d\x3a\x40\xc1" -#MSG="\xbe\x04\x00\x02\x00\x1c\x00\x02\x00\x00\x00" -#MSG="hello" - -echo -en $MSG > /dev/$USB_UART \ No newline at end of file diff --git a/quad/scripts/setup_usb_uart.sh b/quad/scripts/setup_usb_uart.sh deleted file mode 100755 index be12f0e9d1921c16009b5218ad95bc4d3eaa3f06..0000000000000000000000000000000000000000 --- a/quad/scripts/setup_usb_uart.sh +++ /dev/null @@ -1,6 +0,0 @@ -#!/bin/bash - -# The USB device that you are using for UART -USB_DEV=ttyUSB0 - -stty -F /dev/$USB_DEV raw speed 115200 diff --git a/quad/scripts/test_uart_comm.py~ b/quad/scripts/test_uart_comm.py~ deleted file mode 100644 index 2a5c7203a69b03ac667f905e82c95a74e1aaa7dc..0000000000000000000000000000000000000000 --- a/quad/scripts/test_uart_comm.py~ +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/python - -import sys - -print(sys.version_info) -import serial - -def create_msg(main_type, subtype, msg_id, data): - msg = bytes() - msg += b'\xBE' - msg += main_type.to_bytes(1, 'little') - msg += subtype.to_bytes(1, 'little') - msg += msg_id.to_bytes(2, 'little') - msg += len(data).to_bytes(2, 'little') - msg += data - - checksum = 0 - for b in msg: - checksum ^= b - msg += checksum.to_bytes(1, 'little') - return msg - -def create_test_packet(size=8): - data = bytes((i % 256 for i in range(size))) - return create_msg(0, 2, 0, data) - -def read_packet(ser): - header = ser.read(7) - length = int.from_bytes(header[5:7], byteorder='little') - data = ser.read(length) - checksum = ser.read() - return data - -def query_received(ser): - # Send request - query_msg = create_msg(0, 3, 0, b'') - ser.write(query_msg) - ser.flush() - - resp = read_packet(ser) - received_str = resp[:-1].decode() - - return tuple(map(int, received_str.split(','))) - -if __name__ == '__main__': - with serial.Serial('/dev/ttyUSB0', 921600, timeout=5) as ser: - ser.write(create_test_packet(500)) - ser.flush() - print(query_received(ser)) - diff --git a/quad/scripts/tests/run_virtual_test_flight.rb b/quad/scripts/tests/run_virtual_test_flight.rb new file mode 100644 index 0000000000000000000000000000000000000000..17e6bc732e9549101b38ec9fd080493b5f7afa84 --- /dev/null +++ b/quad/scripts/tests/run_virtual_test_flight.rb @@ -0,0 +1,78 @@ +#!/usr/bin/env ruby + +# Test Flight +# +# A simple virtual test flight (take off, hover, and set back down) +# + +script_dir = File.expand_path(File.dirname(__FILE__)) +require script_dir + "/testing_library" + +bin_dir = script_dir + "/../../bin/" +Dir.chdir(bin_dir) + +puts("Firing up the quad...") + +# Start virtual quad +quad = Process.spawn("./virt-quad -q") + +delay_spin_cursor(3) + +################## +# Begin Flight! +################## + +begin + puts("Starting flight...") + + # Set gravity + File.write(I2C_MPU_ACCEL_Z, -1 * GRAVITY) + + puts("Turning on GEAR...") + File.write(GEAR, GEAR_ON) + sleep 0.015 + + puts("Increasing Thrust to half maximum...") + for i in (THROTTLE_MIN..THROTTLE_MID).step(1000) + File.write(THROTTLE, i) + sleep 0.005 + end + + puts("Hovering for 10 seconds") + delay_spin_cursor(10) + + puts("Relaxing thrust to zero") + i = THROTTLE_MID + while i > THROTTLE_MIN + i -= 1000 + File.write(THROTTLE, i) + sleep 0.005 + end + + puts("Swiching off GEAR...") + File.write(GEAR, GEAR_OFF) + + # puts("Collecting logs...") + # msg = "" + # misses = 0 + # fifo = File::open(UART_TX) + # while misses < 10 + # puts "trying..." + # if fifo.eof? + # misses += 1 + # next + # end + # msg += fifo.read() + # end + + # fifo.close() + +# puts msg + + puts("Flight ended successfully."); +ensure + + Process.kill(9, quad) + +end + diff --git a/quad/scripts/tcp_stress_tests.py b/quad/scripts/tests/tcp_stress_tests.py similarity index 100% rename from quad/scripts/tcp_stress_tests.py rename to quad/scripts/tests/tcp_stress_tests.py diff --git a/quad/scripts/tests/test_safety_checks.rb b/quad/scripts/tests/test_safety_checks.rb new file mode 100644 index 0000000000000000000000000000000000000000..922d6439f77b4c245ce1742dbd786f2fcbd81a06 --- /dev/null +++ b/quad/scripts/tests/test_safety_checks.rb @@ -0,0 +1,106 @@ +#!/usr/bin/env ruby + +# Safety Checks +# +# Startup the virtual quad and make sure it doesn't allow combinations of things +# that could hurt people. + +script_dir = File.expand_path(File.dirname(__FILE__)) +require script_dir + "/testing_library" + +bin_dir = script_dir + "/../../bin/" +Dir.chdir(bin_dir) + + +Timeout::timeout(30) { + + puts("Setting up...") + + + sleep 1 + + # Start virtual quad + quad_pid = Process.spawn("./virt-quad -q", + { :rlimit_as => 536870912, # 512 MiB total RAM + :rlimit_stack => 1048576}) # 1 MiB stack + + delay_spin_cursor(5) + + ################# + # Begin Tests + ################# + + begin + + puts("Beginning tests...") + + # Set gravity + File.write(I2C_MPU_ACCEL_Z, -1 * GRAVITY) + + puts("Check that motors are off at startup") + check_motors_are_off + + puts("Check that LED is off at startup") + check_led(0) + + puts("Check that increasing the throttle does nothing to motors") + # (because gear is still off) + for i in (THROTTLE_MIN..THROTTLE_MAX).step(1000) + File.write(THROTTLE, i) + check_motors_are_off + sleep 0.005 + end + + puts("Check that flipping gear to 1 while throttle is high does nothing") + # (motors should still be off, LED should still be off) + File.write(GEAR, GEAR_ON) + sleep 0.015 + check_motors_are_off + i = THROTTLE_MAX + while i > THROTTLE_MID + i -= 1000 + File.write(THROTTLE, i) + check_motors_are_off + check_led 0 + sleep 0.005 + end + + # (swtich GEAR back to off and bring throttle off) + File.write(GEAR, GEAR_OFF) + File.write(THROTTLE, THROTTLE_MIN) + + puts("Check that the LED turns on when gear is flipped on") + # (motors should still be off because our throttle is low) + File.write(GEAR, GEAR_ON) + sleep 0.5 + check_motors_are_off + check_led 1 + + puts("Check that motors turn on") + File.write(THROTTLE, THROTTLE_MID) + averages = get_motor_averages + average = (averages[0] + averages[1] + averages[2] + averages[3])/4 + puts averages, "(#{average})" + assert average.between?(THROTTLE_EIGHTH, MOTOR_MAX) + + puts("Check that gear switch kills the motors") + # (and that light goes off) + File.write(GEAR, GEAR_OFF) + sleep 0.5 + check_motors_are_off + #check_led 0 + + # (Bring the RC throttle back down) + File.write(THROTTLE, THROTTLE_MIN) + + sleep 1 + puts "All safety checks passed." + + ensure + + Process.kill(9, quad_pid) + Process.wait(quad_pid) + + end +} + diff --git a/quad/scripts/test_uart_comm.py b/quad/scripts/tests/test_uart_comm.py similarity index 100% rename from quad/scripts/test_uart_comm.py rename to quad/scripts/tests/test_uart_comm.py diff --git a/quad/scripts/tests/test_unix_uart.rb b/quad/scripts/tests/test_unix_uart.rb new file mode 100644 index 0000000000000000000000000000000000000000..1c9b6a82e4fb3c84ded4038e666378c8b4a5016f --- /dev/null +++ b/quad/scripts/tests/test_unix_uart.rb @@ -0,0 +1,74 @@ +#!/usr/bin/env ruby + +# UART test +# +# This test is pretty simple, just a UART smoke test, using +# the debug callback on the quad + +script_dir = File.expand_path(File.dirname(__FILE__)) +require script_dir + "/testing_library" + +bin_dir = script_dir + "/../../bin/" +Dir.chdir(bin_dir) + + +Timeout::timeout(30) { + + puts("Setting up...") + + sleep 1 + + # Start virtual quad + quad_pid = Process.spawn("./virt-quad -q", + { :rlimit_as => 536870912, # 512 MiB total RAM + :rlimit_stack => 1048576}) # 1 MiB stack + + delay_spin_cursor(5) + + ################# + # Begin Tests + ################# + + begin + + puts("Beginning tests...") + + # Flip gear on + File.write(GEAR, GEAR_ON) + sleep 0.015 + + for j in 1..10 + # Send a debug command + File.write(UART_RX, [0xBE, 1, 0, 0, 0, 0, 0, 0xBF].pack("CCCCCCCC")) + + fifo = File.open(UART_TX) + + # Receive the header + msg = [] + for i in 1..7 + sleep 0.010 + msg.push(fifo.read(1)) + end + + # Receive the remaining data, according to the header specified length + length = msg[5..7].join().unpack("S")[0] + msg = [] + for i in 1..length + sleep 0.010 + msg.push(fifo.read(1)) + end + fifo.close + + puts msg.join() + assert_equal(msg.join().force_encoding("UTF-8"), "Packets received: #{j}") + end + + puts "Basic UART test passed." + + ensure + + Process.kill(9, quad_pid) + Process.wait(quad_pid) + + end +} diff --git a/quad/scripts/test_zybo_uart.py b/quad/scripts/tests/test_zybo_uart.py similarity index 100% rename from quad/scripts/test_zybo_uart.py rename to quad/scripts/tests/test_zybo_uart.py diff --git a/quad/scripts/tests/testing_library.rb b/quad/scripts/tests/testing_library.rb new file mode 100644 index 0000000000000000000000000000000000000000..4deefed674f2cf205b4ad9b0bc6649a5dd882557 --- /dev/null +++ b/quad/scripts/tests/testing_library.rb @@ -0,0 +1,89 @@ +THROTTLE_MIN = 110200 +THROTTLE_MAX = 191900 +THROTTLE_MID = (THROTTLE_MAX + THROTTLE_MIN)/2 +THROTTLE_3_4 = (THROTTLE_MAX + THROTTLE_MID)/2 +THROTTLE_QUAR = (THROTTLE_MID + THROTTLE_MIN)/2 +THROTTLE_EIGHTH = (THROTTLE_QUAR + THROTTLE_MIN)/2 +THROTTLE_16 = (THROTTLE_EIGHTH + THROTTLE_MIN)/2 +MOTOR_MIN = 100000 +MOTOR_MAX = 200000 +GEAR_ON = 170800 +GEAR_OFF = 118300 +GRAVITY = 4096 + +MOTOR1 = "virt-quad-fifos/pwm-output-motor1" +MOTOR2 = "virt-quad-fifos/pwm-output-motor2" +MOTOR3 = "virt-quad-fifos/pwm-output-motor3" +MOTOR4 = "virt-quad-fifos/pwm-output-motor4" + +GEAR = "virt-quad-fifos/pwm-input-gear" +THROTTLE = "virt-quad-fifos/pwm-input-throttle" + +LED = "virt-quad-fifos/mio7-led" + +I2C_MPU_ACCEL_X = "virt-quad-fifos/i2c-mpu-accel-x" +I2C_MPU_ACCEL_Y = "virt-quad-fifos/i2c-mpu-accel-y" +I2C_MPU_ACCEL_Z = "virt-quad-fifos/i2c-mpu-accel-z" + +UART_RX = "virt-quad-fifos/uart-rx" +UART_TX = "virt-quad-fifos/uart-tx" + +require 'test/unit/assertions' +require 'timeout' +require 'thread' +include Test::Unit::Assertions + +$fifos = Hash.new + +def read_fifo_num(f) + if not $fifos.key?(f) + $fifos[f] = File.open(f) + end + $fifos[f].read().chomp.split("\n").last.to_i +end + +# Utility functions +def check_motors_are_off + motor1 = read_fifo_num(MOTOR1) + motor2 = read_fifo_num(MOTOR2) + motor3 = read_fifo_num(MOTOR3) + motor4 = read_fifo_num(MOTOR4) + assert_operator motor1, :<=, THROTTLE_MIN + assert_operator motor2, :<=, THROTTLE_MIN + assert_operator motor3, :<=, THROTTLE_MIN + assert_operator motor4, :<=, THROTTLE_MIN +end + +def get_motor_averages + motors = [[], [], [], []] + for i in 0..100 + motors[0].push(read_fifo_num(MOTOR1)) + motors[1].push(read_fifo_num(MOTOR2)) + motors[2].push(read_fifo_num(MOTOR3)) + motors[3].push(read_fifo_num(MOTOR4)) + sleep 0.010 + end + average = [] + average[0] = motors[0].inject(:+).to_f / motors[0].size + average[1] = motors[1].inject(:+).to_f / motors[1].size + average[2] = motors[2].inject(:+).to_f / motors[2].size + average[3] = motors[3].inject(:+).to_f / motors[3].size + average +end + +def check_led(is_on) + led = read_fifo_num(LED) + assert_equal(is_on, led) +end + +def delay_spin_cursor(delay) + fps = 10 + chars = %w[| / - \\] + iteations = delay * fps + iter = 0 + iteations.times() do + print chars[(iter+=1) % chars.length] + sleep (1.0/fps) + print "\b" + end +end diff --git a/quad/scripts/uart_stress_tests.py b/quad/scripts/tests/uart_stress_tests.py similarity index 100% rename from quad/scripts/uart_stress_tests.py rename to quad/scripts/tests/uart_stress_tests.py diff --git a/quad/scripts/uart_comm_listen.py b/quad/scripts/uart_comm_listen.py deleted file mode 100755 index 0a251b5df409f1ffcb1dfc121b8efc793a1ee220..0000000000000000000000000000000000000000 --- a/quad/scripts/uart_comm_listen.py +++ /dev/null @@ -1,28 +0,0 @@ -#!/usr/local/bin/python3.6 - -import sys -import time - -import serial - -def read_packet(ser): - header = ser.read(7) - length = int.from_bytes(header[5:7], byteorder='little') - data = ser.read(length) - checksum = ser.read() - return data - -if __name__ == '__main__': - with serial.Serial('/dev/ttyUSB0', 921600, timeout=5) as ser: - i = 0 - while True: - ser.reset_input_buffer() - time.sleep(0.05) - while ser.in_waiting != 0: - resp = read_packet(ser) - elapsed = int.from_bytes(resp[0:3], byteorder='little') - processed = int.from_bytes(resp[4:7], byteorder='little') - print("{} {} {}".format(i, elapsed, processed)) - i += 1 - ser.flush() - diff --git a/quad/scripts/uart_comm_send.py b/quad/scripts/uart_comm_send.py deleted file mode 100755 index 430a6b2874232192be2a6d79436eb1c4807e5115..0000000000000000000000000000000000000000 --- a/quad/scripts/uart_comm_send.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/local/bin/python3.6 - -import sys -import time - -import serial - -def create_msg(main_type, subtype, msg_id, data): - msg = bytes() - msg += b'\xBE' - msg += main_type.to_bytes(1, 'little') - msg += subtype.to_bytes(1, 'little') - msg += msg_id.to_bytes(2, 'little') - msg += len(data).to_bytes(2, 'little') - msg += data - - checksum = 0 - for b in msg: - checksum ^= b - msg += checksum.to_bytes(1, 'little') - return msg - -def create_test_packet(size=8): - data = bytes((i % 256 for i in range(size))) - return create_msg(0, 2, 0, data) - -if __name__ == '__main__': - with serial.Serial('/dev/ttyUSB0', 921600, timeout=5) as ser: - for i in range(5): - ser.reset_input_buffer() - data = bytes.fromhex('be040002001c0002000000d80471be5732703f9d16093f8bf7a03d0586ab3d006d3a40c1') - #ser.write(create_test_packet(24)) - ser.write(data) - #ser.flush() - #time.sleep(0.5) diff --git a/quad/scripts/build_zybo.sh b/quad/scripts/xsdk/build_zybo.sh similarity index 100% rename from quad/scripts/build_zybo.sh rename to quad/scripts/xsdk/build_zybo.sh diff --git a/quad/scripts/clean_xsdk_workspace.sh b/quad/scripts/xsdk/clean_xsdk_workspace.sh similarity index 100% rename from quad/scripts/clean_xsdk_workspace.sh rename to quad/scripts/xsdk/clean_xsdk_workspace.sh diff --git a/quad/scripts/create_zybo_boot.sh b/quad/scripts/xsdk/create_zybo_boot.sh similarity index 100% rename from quad/scripts/create_zybo_boot.sh rename to quad/scripts/xsdk/create_zybo_boot.sh diff --git a/quad/scripts/old_quad_build.sh b/quad/scripts/xsdk/old_quad_build.sh similarity index 100% rename from quad/scripts/old_quad_build.sh rename to quad/scripts/xsdk/old_quad_build.sh diff --git a/quad/src/commands/cb_default.h b/quad/src/commands/cb_default.h index 5581c442c29af074806052203d4e18e76d263d5c..c1b95ebed399b76f53f91a128b623c85d94cf332 100644 --- a/quad/src/commands/cb_default.h +++ b/quad/src/commands/cb_default.h @@ -1,10 +1,9 @@ #include "commands.h" - /* The cb_default used on the groundStation. This file MUST NOT BE INCLUDED * by anything except for commands.c */ /* cb_default used by portable commands.c */ -int cb_default(struct modular_structs *structs) +int cb_default(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { return 0; } diff --git a/quad/src/commands/commands.h b/quad/src/commands/commands.h index 2d41d2e6294c74757518e51b8157df6351765667..194bbaedcb7ac1661035e721da865fc038db8a34 100644 --- a/quad/src/commands/commands.h +++ b/quad/src/commands/commands.h @@ -4,6 +4,7 @@ #include <stdio.h> #include <stdlib.h> #include <string.h> +#include <stdint.h> #define MAX_CMD_TEXT_LENGTH 100 @@ -56,7 +57,14 @@ enum MessageTypeID{ }; struct modular_structs; -struct metadata; + +struct metadata { + char begin_char; + uint16_t msg_type; + uint16_t msg_id; + uint16_t data_len; +}; + typedef int (command_cb)(struct modular_structs *, struct metadata *, unsigned char *, unsigned short); /* diff --git a/quad/src/computation_graph/computation_graph.c b/quad/src/computation_graph/computation_graph.c index 7b21b2273e111b96160293108fa08aed2b7de5d5..81ebbf44e5dbdd5e07d039619d26093c4f53ce16 100644 --- a/quad/src/computation_graph/computation_graph.c +++ b/quad/src/computation_graph/computation_graph.c @@ -9,11 +9,19 @@ // Array to store input values for passing to the execute function of each node static double exec_input_vals[GRAPH_MAX_INPUTS]; +// Macro functions for setting and clearing single bits in int array +// From http://www.mathcs.emory.edu/~cheung/Courses/255/Syllabus/1-C-intro/bit-array.html +#define setBit(A,k) ( A[(k / (8*sizeof(*A)))] |= (1 << (k % (8*sizeof(*A)))) ) +#define clearBit(A,k) ( A[(k / (8*sizeof(*A)))] &= ~(1 << (k % (8*sizeof(*A)))) ) +#define testBit(A,k) ( A[(k / (8*sizeof(*A)))] & (1 << (k % (8*sizeof(*A)))) ) + struct computation_graph *create_graph() { struct computation_graph *the_graph = malloc(sizeof(struct computation_graph)); if (!the_graph) {return NULL;} + // Allocate space for a single node in the graph the_graph->nodes = malloc(sizeof(struct graph_node)); - if (!the_graph->nodes) { return NULL; } + the_graph->node_existence = malloc(sizeof(int)); + if (!the_graph->nodes || !the_graph->node_existence) { return NULL; } the_graph->n_nodes = 0; the_graph->size = 1; return the_graph; @@ -46,12 +54,14 @@ static void reset_node_rec(struct computation_graph* graph, int node_id, int dep } int reset_node(struct computation_graph* graph, int node_id) { - if (node_id >= graph->n_nodes) { + if (!graph_node_exists(graph, node_id)) { return -1; } int i; - for (i = 0; i < graph->n_nodes; i++) { - graph->nodes[i].processed_state = UNPROCESSED; + for (i = 0; i < graph->size; i++) { + if (graph_node_exists(graph, i)) { + graph->nodes[i].processed_state = UNPROCESSED; + } } reset_node_rec(graph, node_id, 0); return 0; @@ -59,12 +69,13 @@ int reset_node(struct computation_graph* graph, int node_id) { int graph_set_source(struct computation_graph *graph, int dest_node_id, int dest_input, int src_node_id, int src_output) { - if (dest_node_id >= graph->n_nodes || src_node_id >= graph->n_nodes) { + if (!graph_node_exists(graph, dest_node_id) || !graph_node_exists(graph, src_node_id)) { return -1; } struct graph_node *dest_node = &graph->nodes[dest_node_id]; struct graph_node *src_node = &graph->nodes[src_node_id]; - if (dest_input >= dest_node->type->n_inputs || src_output >= src_node->type->n_outputs) { + if (dest_input >= dest_node->type->n_inputs || src_output >= src_node->type->n_outputs || + dest_input < 0 || src_output < 0) { return -1; } @@ -82,7 +93,7 @@ int graph_set_source(struct computation_graph *graph, } struct node_src graph_get_source(struct computation_graph *graph, int node_id, int input_id) { - if (node_id >= graph->n_nodes || node_id < 0 || + if (!graph_node_exists(graph, node_id) || input_id >= graph->nodes[node_id].type->n_inputs || input_id < 0) { return (struct node_src) {.controller_id = -1, .controller_output = -1}; } @@ -95,16 +106,33 @@ int graph_add_node(struct computation_graph *graph, void *state) { assert(type->n_inputs <= GRAPH_MAX_INPUTS); int new_id = graph->n_nodes; - if (new_id >= graph->size) { - int new_capacity = graph->n_nodes == 0 ? 1 : graph->n_nodes * 2; - struct graph_node *node_arr = realloc(graph->nodes, sizeof(struct graph_node) * new_capacity); - if (!node_arr) { - return -1; + return graph_add_node_id(graph, new_id, name, type, state); +} + +int graph_add_node_id(struct computation_graph *graph, + int id, + const char *name, + const struct graph_node_type *type, + void *state) { + if (id >= graph->size) { + size_t old_size = graph->size; + size_t new_size = old_size == 0 ? 8 : id * 2; // Hold twice the given ID + struct graph_node *node_arr = realloc(graph->nodes, sizeof(struct graph_node) * new_size); + if (!node_arr) { return -1; } + // Number of integers needed to hold new_size bits + size_t new_exist_size = ceil((float)new_size / (8 * sizeof(int))); // ceil(new_size / (bits per int)) + // Set the newly allocated memory to 0 + size_t old_exist_size = ceil((float)old_size / (8 * sizeof(int))); + if (old_exist_size != new_exist_size) { + int* exist_arr = realloc(graph->node_existence, sizeof(int) * new_exist_size); + if (!exist_arr) {return -1;} + memset(exist_arr + old_exist_size, 0, (new_exist_size - old_exist_size) * sizeof(int)); + graph->node_existence = exist_arr; } - graph->size = new_capacity; + graph->size = new_size; graph->nodes = node_arr; } - struct graph_node *new_node = &graph->nodes[new_id]; + struct graph_node *new_node = &graph->nodes[id]; new_node->name = strdup(name); new_node->type = type; new_node->state = state; @@ -124,15 +152,16 @@ int graph_add_node(struct computation_graph *graph, new_node->input_srcs[i].controller_id = -1; } graph->n_nodes += 1; + setBit(graph->node_existence, id); // Reset block upon creation if (new_node->type->reset != NULL) { new_node->type->reset(new_node->state); } - return new_id; + return id; } int graph_set_param_val(struct computation_graph *graph, int node_id, int param_id, double value) { - if (node_id >= graph->n_nodes || param_id >= graph->nodes[node_id].type->n_params) { + if (!graph_node_exists(graph, node_id) || param_id >= graph->nodes[node_id].type->n_params) { return -1; } graph->nodes[node_id].param_values[param_id] = value; @@ -141,27 +170,33 @@ int graph_set_param_val(struct computation_graph *graph, int node_id, int param_ } double graph_get_param_val(const struct computation_graph *graph, int node_id, int param_id) { - if (node_id >= graph->n_nodes || param_id >= graph->nodes[node_id].type->n_params) { + if (!graph_node_exists(graph, node_id) || param_id >= graph->nodes[node_id].type->n_params) { return NAN; } return graph->nodes[node_id].param_values[param_id]; } double graph_get_output(const struct computation_graph *graph, int node_id, int output_id) { - if (node_id >= graph->n_nodes || output_id >= graph->nodes[node_id].type->n_outputs) { + if (!graph_node_exists(graph, node_id) || output_id >= graph->nodes[node_id].type->n_outputs) { return NAN; } return graph->nodes[node_id].output_values[output_id]; } +/* + * Assumptions: The node passed in is a valid ID (should be checked before passing) + * and all node sources are either valid node-output pairs, or the source node ID == -1 + * These constraints should be satisfied by using the graph_set_source function, so long as + * a valid node ID is passed in to the first call of this function +*/ void graph_compute_node_rec(struct computation_graph *graph, int node_id, int depth) { if (depth >= GRAPH_MAX_DEPTH) { - assert(1 == 0); // TODO :Xil_Assert false - return; - } - if (node_id >= graph->n_nodes) { + assert(1 == 0); return; } + // if (!graph_node_exists(graph, node_id)) { + // return; + // } struct graph_node *node = &graph->nodes[node_id]; if (node->processed_state != UNPROCESSED) { return; @@ -197,17 +232,19 @@ void graph_compute_node_rec(struct computation_graph *graph, int node_id, int de void graph_compute_nodes(struct computation_graph *graph, int* node_ids, int n_nodes) { int i; - for (i = 0; i < graph->n_nodes; i++) { + for (i = 0; i < graph->size; i++) { + // Note: Do not access malloc'd members in here without first checking if node is valid graph->nodes[i].processed_state = UNPROCESSED; } for (i = 0; i < n_nodes; i++) { int node_id = node_ids[i]; - if (node_id < graph->n_nodes) { + if (graph_node_exists(graph, node_id)) { graph_compute_node_rec(graph, node_id, 0); } } // Clear all the updated flags for nodes that were actually executed - for (i = 0; i < graph->n_nodes; i++) { + for (i = 0; i < graph->size; i++) { + // Note: Do not access malloc'd members in here without first checking if node is valid struct graph_node* node = &graph->nodes[i]; if (node->processed_state == PROCESSED) { node->updated = 0; @@ -221,7 +258,8 @@ int export_dot(const struct computation_graph* graph, FILE* of, int print_output // Draw all the nodes and their inputs int i; - for (i = 0; i < graph->n_nodes; i++) { + for (i = 0; i < graph->size; i++) { + if (!graph_node_exists(graph, i)) {continue;} struct graph_node *node = &graph->nodes[i]; // Create node fprintf(of, "\"%s\"[shape=record\nlabel=\"", node->name); @@ -254,3 +292,10 @@ int export_dot(const struct computation_graph* graph, FILE* of, int print_output fprintf(of, "}"); // Close graph return 0; } + +int graph_node_exists(const struct computation_graph *graph, int node_id) { + if (node_id < 0 || node_id >= graph->size || !testBit(graph->node_existence, node_id)) { + return 0; + } + else {return 1;} +} diff --git a/quad/src/computation_graph/computation_graph.h b/quad/src/computation_graph/computation_graph.h index e997aa7ab06a79d61aac152699d9a49379403ffc..adddf5119ff742f9f2a603936c8d3b59ae4c6deb 100644 --- a/quad/src/computation_graph/computation_graph.h +++ b/quad/src/computation_graph/computation_graph.h @@ -21,6 +21,7 @@ struct computation_graph { int n_nodes; int size; struct graph_node *nodes; + int* node_existence; // Single-bit values indicating whether a node with a particular ID exists }; // Declares a node type @@ -89,6 +90,18 @@ int graph_add_node(struct computation_graph *graph, const struct graph_node_type *type, void *state); +/* + * Similar to graph_add_node, but adds with a specific ID + * WARNING: Do not try to use this to create nodes with arbitrary IDs, + * as it stores IDs sequentially in an array, so a large ID will result + * in at least that many elements being allocated + */ +int graph_add_node_id(struct computation_graph *graph, + int id, + const char *name, + const struct graph_node_type *type, + void *state); + /* * Returns the value at the output of the requested node for the requested output. * Returns 0 if the given node or output IDs are invalid @@ -114,6 +127,12 @@ double graph_get_param_val(const struct computation_graph *graph, int node_id, i */ void graph_compute_nodes(struct computation_graph *graph, int* node_ids, int n_nodes); +/* + * Check if a particular node with a given ID has been added + * Returns 1 if node exists, 0 otherwise + */ +int graph_node_exists(const struct computation_graph *graph, int node_id); + /* * Writes a graphical representation of the given graph to <of> in the DOT language */ diff --git a/quad/src/computation_graph/test/test_computation_graph.c b/quad/src/computation_graph/test/test_computation_graph.c index 929fe9ca44404efbaa9e46287cc78a6a2fe057f9..b0b6a14505ce0ca581f02ff82a2d1d010efe42b5 100644 --- a/quad/src/computation_graph/test/test_computation_graph.c +++ b/quad/src/computation_graph/test/test_computation_graph.c @@ -241,6 +241,28 @@ int graph_test_get_source_null() { } } +int graph_test_add_by_id() { + struct computation_graph *graph = create_graph(); + int desired_id = 87; + int add_block = graph_add_node_id(graph, desired_id, "Add", &node_add_type, NULL); + if (add_block != desired_id) { + return -1; + } + int const1 = graph_add_node_id(graph, 12, "const1", &node_const_type, NULL); + graph_set_param_val(graph, const1, CONST_SET, 3.5); + int const2 = graph_add_node_id(graph, 123, "const2", &node_const_type, NULL); + graph_set_param_val(graph, const2, CONST_SET, 2.5); + graph_set_source(graph, add_block, ADD_SUMMAND1, const1, CONST_VAL); + graph_set_source(graph, add_block, ADD_SUMMAND2, const2, CONST_VAL); + + int to_compute_for[] = {add_block}; + graph_compute_nodes(graph, to_compute_for, 1); + double result = graph_get_output(graph, add_block, ADD_SUM); + printf("n_nodes: %d, size: %d\n", graph->n_nodes, graph->size); + printf("result: %f", result); + return nequal(result, 3.5 + 2.5); +} + int main() { test(graph_test_one_add, "Test adding 2 numbers"); test(graph_test_circular_runs, "Test computing cycles"); @@ -254,5 +276,6 @@ int main() { test(graph_test_update_disconnected, "Tests that nodes get executed when updated, even if disconnected"); test(graph_test_get_source, "Tests that the get_source call works normally"); test(graph_test_get_source_null, "Tests that the get_source call returns ID -1 when invalid ID is passed"); + test(graph_test_add_by_id, "Tests that new nodes can be created by ID"); return test_summary(); } diff --git a/quad/src/gen_diagram/Makefile b/quad/src/gen_diagram/Makefile index cf33639c89282e9d326a0120b4f0d47fbbb26827..bf0f58c8c1c5260c10aef4d5f1634309183bcbb3 100644 --- a/quad/src/gen_diagram/Makefile +++ b/quad/src/gen_diagram/Makefile @@ -1,9 +1,11 @@ - -QUAD_BLOCKS = ../src/graph_blocks - -gen_diagram: generate.c ../src/control_algorithm.c ../src/computation_graph.c - gcc -o gen_diagram -I. -I../src/ generate.c ../src/computation_graph.c ../src/control_algorithm.c ../src/graph_blocks/*.c -Dread_flap=freadflap -Dget_last_loop_time=fgettime - -.PHONY: clean -clean: - rm gen_diagram +TOP=../.. + +NAME = gen_diagram +REQLIBS = -lquad_app -lgraph_blocks -lcomputation_graph -lm + +include $(TOP)/executable.mk + +diagram: + $(MAKE) -C ../quad_app + $(MAKE) clean default + ./create_png.sh \ No newline at end of file diff --git a/quad/src/gen_diagram/README.md b/quad/src/gen_diagram/README.md index 87b45825befd9e43f373eab8b973ba098e9cd147..3d2d7db362692e39303670476d120f22d51d6543 100644 --- a/quad/src/gen_diagram/README.md +++ b/quad/src/gen_diagram/README.md @@ -1,9 +1,4 @@ -The gen_diagram project can create an image of the controller network. Below outlines the process of how to use it. +The gen_diagram project can create an image of the controller network. -Within the `quad/sw/modular_quad_pid` directory: - -1. Within the `gen_diagram` folder, run `make` to build the new code. -2. Now execute the program with `./gen_diagram` -3. If you have graphviz installed, you can run `dot -Tpng network.dot -o network.png` to generate a PNG file of the graph. - -Enjoy your new diagram! +To make a new diagram, from the top-level quad directory, run "make gen_diagram". +The new network.png file show up in this folder. \ No newline at end of file diff --git a/quad/src/gen_diagram/create_png.sh b/quad/src/gen_diagram/create_png.sh index 3389781bf0d69d913c2b8d10e055ff2945bc3846..5c4a2939cf9eda23eb267bc95ca3e6818ce4e846 100755 --- a/quad/src/gen_diagram/create_png.sh +++ b/quad/src/gen_diagram/create_png.sh @@ -1,7 +1,6 @@ #/bin/bash -make -./gen_diagram - +cd $(dirname $0) +./../../bin/gen_diagram dot -Tpng network.dot -o network.png diff --git a/quad/src/gen_diagram/gen_diagram b/quad/src/gen_diagram/gen_diagram deleted file mode 100755 index 8413df5adf030804107bf812502da5249bf17b24..0000000000000000000000000000000000000000 Binary files a/quad/src/gen_diagram/gen_diagram and /dev/null differ diff --git a/quad/src/gen_diagram/generate.c b/quad/src/gen_diagram/generate.c index da5f3c3835bba723c55999d257a935ddf340aa6c..3e712a2c04ded92ebc4e3465fcfb5404b466af19 100644 --- a/quad/src/gen_diagram/generate.c +++ b/quad/src/gen_diagram/generate.c @@ -1,21 +1,9 @@ #include <stdio.h> - #include "computation_graph.h" -#include "node_pid.h" -#include "node_bounds.h" -#include "node_constant.h" -#include "node_mixer.h" -#include "PID.h" #include "control_algorithm.h" -#define ROLL_PITCH_MAX_ANGLE 0.3490 // 20 degrees -parameter_t ps; - -//int control_algorithm_init(parameter_t * ps); -int freadflap(int i) {return i;} -float fgettime() {return 0.0;} - int main() { + parameter_t ps; control_algorithm_init(&ps); FILE* dot_fp; dot_fp = fopen("network.dot", "w"); diff --git a/quad/src/gen_diagram/network.dot b/quad/src/gen_diagram/network.dot index 6c7ff17339d512cd4468ece1ac8c74a7e7b86183..25a5dc165c2dac141e2c6694b707ec96db8eaf4a 100644 --- a/quad/src/gen_diagram/network.dot +++ b/quad/src/gen_diagram/network.dot @@ -1,47 +1,47 @@ digraph G { rankdir="LR" "Roll PID"[shape=record -label="<f0>Roll PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=15.000] |<f5> [Ki=0.000] |<f6> [Kd=0.200]"] -"VRPN Roll" -> "Roll PID":f1 [label="Constant"] -"Y pos PID" -> "Roll PID":f2 [label="Correction"] -"Ts_VRPN" -> "Roll PID":f3 [label="Constant"] +label="<f0>Roll PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=15.000] |<f5> [Ki=0.000] |<f6> [Kd=0.200] |<f7> [alpha=0.000]"] +"Roll" -> "Roll PID":f1 [label="Constant"] +"Y Vel PID" -> "Roll PID":f2 [label="Correction"] +"Ts_IMU" -> "Roll PID":f3 [label="Constant"] "Pitch PID"[shape=record -label="<f0>Pitch PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=15.000] |<f5> [Ki=0.000] |<f6> [Kd=0.200]"] -"VRPN Pitch" -> "Pitch PID":f1 [label="Constant"] -"X pos PID" -> "Pitch PID":f2 [label="Correction"] -"Ts_VRPN" -> "Pitch PID":f3 [label="Constant"] +label="<f0>Pitch PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=15.000] |<f5> [Ki=0.000] |<f6> [Kd=0.200] |<f7> [alpha=0.000]"] +"Pitch trim add" -> "Pitch PID":f1 [label="Sum"] +"X Vel PID" -> "Pitch PID":f2 [label="Correction"] +"Ts_IMU" -> "Pitch PID":f3 [label="Constant"] "Yaw PID"[shape=record -label="<f0>Yaw PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=2.600] |<f5> [Ki=0.000] |<f6> [Kd=0.000]"] +label="<f0>Yaw PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=2.600] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] "Yaw" -> "Yaw PID":f1 [label="Constant"] "Yaw Setpoint" -> "Yaw PID":f2 [label="Constant"] "Ts_VRPN" -> "Yaw PID":f3 [label="Constant"] "Roll Rate PID"[shape=record -label="<f0>Roll Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=4600.000] |<f5> [Ki=0.000] |<f6> [Kd=550.000]"] +label="<f0>Roll Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=4600.000] |<f5> [Ki=0.000] |<f6> [Kd=550.000] |<f7> [alpha=0.000]"] "dPhi" -> "Roll Rate PID":f1 [label="Constant"] "Roll PID" -> "Roll Rate PID":f2 [label="Correction"] "Ts_IMU" -> "Roll Rate PID":f3 [label="Constant"] "Pitch Rate PID"[shape=record -label="<f0>Pitch Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=4600.000] |<f5> [Ki=0.000] |<f6> [Kd=550.000]"] +label="<f0>Pitch Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=4600.000] |<f5> [Ki=0.000] |<f6> [Kd=550.000] |<f7> [alpha=0.000]"] "dTheta" -> "Pitch Rate PID":f1 [label="Constant"] "Pitch PID" -> "Pitch Rate PID":f2 [label="Correction"] "Ts_IMU" -> "Pitch Rate PID":f3 [label="Constant"] "Yaw Rate PID"[shape=record -label="<f0>Yaw Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=435480.000] |<f5> [Ki=0.000] |<f6> [Kd=0.000]"] +label="<f0>Yaw Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=29700.000] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] "dPsi" -> "Yaw Rate PID":f1 [label="Constant"] "Yaw PID" -> "Yaw Rate PID":f2 [label="Correction"] "Ts_IMU" -> "Yaw Rate PID":f3 [label="Constant"] "X pos PID"[shape=record -label="<f0>X pos PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=-0.015] |<f5> [Ki=-0.005] |<f6> [Kd=-0.030]"] +label="<f0>X pos PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=-0.015] |<f5> [Ki=-0.005] |<f6> [Kd=-0.030] |<f7> [alpha=0.000]"] "VRPN X" -> "X pos PID":f1 [label="Constant"] "X Setpoint" -> "X pos PID":f2 [label="Constant"] "Ts_VRPN" -> "X pos PID":f3 [label="Constant"] "Y pos PID"[shape=record -label="<f0>Y pos PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.015] |<f5> [Ki=0.005] |<f6> [Kd=0.030]"] +label="<f0>Y pos PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.015] |<f5> [Ki=0.005] |<f6> [Kd=0.030] |<f7> [alpha=0.000]"] "VRPN Y" -> "Y pos PID":f1 [label="Constant"] "Y Setpoint" -> "Y pos PID":f2 [label="Constant"] "Ts_VRPN" -> "Y pos PID":f3 [label="Constant"] "Altitude PID"[shape=record -label="<f0>Altitude PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=9804.000] |<f5> [Ki=817.000] |<f6> [Kd=7353.000]"] +label="<f0>Altitude PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=9804.000] |<f5> [Ki=817.000] |<f6> [Kd=7353.000] |<f7> [alpha=0.000]"] "VRPN Alt" -> "Altitude PID":f1 [label="Constant"] "Alt Setpoint" -> "Altitude PID":f2 [label="Constant"] "Ts_VRPN" -> "Altitude PID":f3 [label="Constant"] @@ -65,6 +65,12 @@ label="<f0>Pitch |<f1> [Constant=0.000]"] label="<f0>Roll |<f1> [Constant=0.000]"] "Yaw"[shape=record label="<f0>Yaw |<f1> [Constant=0.000]"] +"Pitch trim"[shape=record +label="<f0>Pitch trim |<f1> [Constant=0.020]"] +"Pitch trim add"[shape=record +label="<f0>Pitch trim add |<f1> --\>Summand 1 |<f2> --\>Summand 2"] +"Pitch trim" -> "Pitch trim add":f1 [label="Constant"] +"Pitch" -> "Pitch trim add":f2 [label="Constant"] "dTheta"[shape=record label="<f0>dTheta |<f1> [Constant=0.000]"] "dPhi"[shape=record @@ -72,13 +78,13 @@ label="<f0>dPhi |<f1> [Constant=0.000]"] "dPsi"[shape=record label="<f0>dPsi |<f1> [Constant=0.000]"] "P PWM Clamp"[shape=record -label="<f0>P PWM Clamp |<f1> --\>Bounds in |<f2> [Min=-30000.000] |<f3> [Max=30000.000]"] +label="<f0>P PWM Clamp |<f1> --\>Bounds in |<f2> [Min=-20000.000] |<f3> [Max=20000.000]"] "Pitch Rate PID" -> "P PWM Clamp":f1 [label="Correction"] "R PWM Clamp"[shape=record -label="<f0>R PWM Clamp |<f1> --\>Bounds in |<f2> [Min=-30000.000] |<f3> [Max=30000.000]"] +label="<f0>R PWM Clamp |<f1> --\>Bounds in |<f2> [Min=-20000.000] |<f3> [Max=20000.000]"] "Roll Rate PID" -> "R PWM Clamp":f1 [label="Correction"] "Y PWM Clamp"[shape=record -label="<f0>Y PWM Clamp |<f1> --\>Bounds in |<f2> [Min=-30000.000] |<f3> [Max=30000.000]"] +label="<f0>Y PWM Clamp |<f1> --\>Bounds in |<f2> [Min=-20000.000] |<f3> [Max=20000.000]"] "Yaw Rate PID" -> "Y PWM Clamp":f1 [label="Correction"] "VRPN X"[shape=record label="<f0>VRPN X |<f1> [Constant=0.000]"] @@ -100,11 +106,44 @@ label="<f0>RC Yaw |<f1> [Constant=0.000]"] label="<f0>RC Throttle |<f1> [Constant=0.000]"] "Signal Mixer"[shape=record label="<f0>Signal Mixer |<f1> --\>Throttle |<f2> --\>Pitch |<f3> --\>Roll |<f4> --\>Yaw"] +"T trim add" -> "Signal Mixer":f1 [label="Sum"] "P PWM Clamp" -> "Signal Mixer":f2 [label="Bounded"] "R PWM Clamp" -> "Signal Mixer":f3 [label="Bounded"] "Y PWM Clamp" -> "Signal Mixer":f4 [label="Bounded"] "Ts_IMU"[shape=record -label="<f0>Ts_IMU |<f1> [Constant=0.000]"] +label="<f0>Ts_IMU |<f1> [Constant=0.005]"] "Ts_VRPN"[shape=record -label="<f0>Ts_VRPN |<f1> [Constant=0.000]"] +label="<f0>Ts_VRPN |<f1> [Constant=0.040]"] +"zero"[shape=record +label="<f0>zero |<f1> [Constant=0.000]"] +"X Vel PID"[shape=record +label="<f0>X Vel PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] +"X Vel" -> "X Vel PID":f1 [label="Correction"] +"X Vel Clamp" -> "X Vel PID":f2 [label="Bounded"] +"Ts_VRPN" -> "X Vel PID":f3 [label="Constant"] +"Y Vel PID"[shape=record +label="<f0>Y Vel PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] +"Y Vel" -> "Y Vel PID":f1 [label="Correction"] +"Y vel Clamp" -> "Y Vel PID":f2 [label="Bounded"] +"Ts_VRPN" -> "Y Vel PID":f3 [label="Constant"] +"X Vel"[shape=record +label="<f0>X Vel |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=1.000] |<f7> [alpha=0.000]"] +"VRPN X" -> "X Vel":f1 [label="Constant"] +"zero" -> "X Vel":f2 [label="Constant"] +"Ts_VRPN" -> "X Vel":f3 [label="Constant"] +"Y Vel"[shape=record +label="<f0>Y Vel |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=1.000] |<f7> [alpha=0.000]"] +"VRPN Y" -> "Y Vel":f1 [label="Constant"] +"zero" -> "Y Vel":f2 [label="Constant"] +"Ts_VRPN" -> "Y Vel":f3 [label="Constant"] +"X Vel Clamp"[shape=record +label="<f0>X Vel Clamp |<f1> --\>Bounds in |<f2> [Min=-2.000] |<f3> [Max=2.000]"] +"X pos PID" -> "X Vel Clamp":f1 [label="Correction"] +"Y vel Clamp"[shape=record +label="<f0>Y vel Clamp |<f1> --\>Bounds in |<f2> [Min=-2.000] |<f3> [Max=2.000]"] +"Y pos PID" -> "Y vel Clamp":f1 [label="Correction"] +"X Stick Gain"[shape=record +label="<f0>X Stick Gain |<f1> --\>Input |<f2> [Gain=5.000]"] +"Y Stick Gain"[shape=record +label="<f0>Y Stick Gain |<f1> --\>Input |<f2> [Gain=-5.000]"] } \ No newline at end of file diff --git a/quad/src/gen_diagram/network.png b/quad/src/gen_diagram/network.png index 6734445acec05b986f97fb83855e62a39ee27463..6e1c3ebc4db038a6d42839315233e453f2e123fe 100644 Binary files a/quad/src/gen_diagram/network.png and b/quad/src/gen_diagram/network.png differ diff --git a/quad/src/graph_blocks/node_pid.c b/quad/src/graph_blocks/node_pid.c index df6b611100aec808a8728a3fbe435ecbe5078557..e776b7ed28e9295c9f30be9adb104ae3e9598647 100644 --- a/quad/src/graph_blocks/node_pid.c +++ b/quad/src/graph_blocks/node_pid.c @@ -6,9 +6,10 @@ static double FLT_EPSILON = 0.0001; struct pid_node_state { - double prev_error; // Previous error + double prev_val; // Previous input value double acc_error; // Accumulated error double last_filtered; // Last output from the filtered derivative + int just_reset; // Set to 1 after a call to reset }; // The generic PID diagram. This function takes in pid inputs (CUR_POINT and SETOINT) and calculates the output "pid_correction" @@ -50,23 +51,29 @@ static void pid_computation(void *state, const double* params, const double *inp pid_state->acc_error += error; } + if (pid_state->just_reset) { + // On first call after a reset, set the previous value to + // the current value to prevent a spike in derivative + pid_state->prev_val = inputs[PID_CUR_POINT]; + pid_state->just_reset = 0; + } // Compute each term's contribution P = params[PID_KP] * error; I = params[PID_KI] * pid_state->acc_error * inputs[PID_DT]; // Low-pass filter on derivative - double change_in_error = error - pid_state->prev_error; + double change_in_value = inputs[PID_CUR_POINT] - pid_state->prev_val; double term1 = params[PID_ALPHA] * pid_state->last_filtered; - double derivative = change_in_error / inputs[PID_DT]; + double derivative = change_in_value / inputs[PID_DT]; if (inputs[PID_DT] == 0) { // Divide by zero check derivative = 0; } double term2 = params[PID_KD] * (1.0f - params[PID_ALPHA]) * derivative; D = term1 + term2; pid_state->last_filtered = D; // Store filtered value for next filter iteration - pid_state->prev_error = error; // Store the current error into the state + pid_state->prev_val = inputs[PID_CUR_POINT]; // Store the current error into the state - outputs[PID_CORRECTION] = P + I + D; // Store the computed correction + outputs[PID_CORRECTION] = P + I - D; // Store the computed correction } // This function sets the accumulated error and previous error to 0 @@ -74,8 +81,8 @@ static void pid_computation(void *state, const double* params, const double *inp static void reset_pid(void *state) { struct pid_node_state* pid_state = (struct pid_node_state*)state; pid_state->acc_error = 0; - pid_state->prev_error = 0; pid_state->last_filtered = 0; + pid_state->just_reset = 1; } diff --git a/quad/src/quad_app/PID.h b/quad/src/quad_app/PID.h index 4c5e4b81f0273a9a62aa175b6c0f350914fb67a2..5a83225b0b9813e4d311bf61c8f1eae89c7f24a0 100644 --- a/quad/src/quad_app/PID.h +++ b/quad/src/quad_app/PID.h @@ -21,7 +21,7 @@ //#define YAW_ANGLE_KD 0.0f // when using units of radians -#define YAW_ANGULAR_VELOCITY_KP 190.0f * 2292.0f//200.0f * 2292.0f +#define YAW_ANGULAR_VELOCITY_KP 29700//200.0f * 2292.0f #define YAW_ANGULAR_VELOCITY_KI 0.0f #define YAW_ANGULAR_VELOCITY_KD 0.0f #define YAW_ANGLE_KP 2.6f diff --git a/quad/src/quad_app/biquad_filter.c b/quad/src/quad_app/biquad_filter.c new file mode 100644 index 0000000000000000000000000000000000000000..3fb3327e4106aea63f68b1f017508b20879337e3 --- /dev/null +++ b/quad/src/quad_app/biquad_filter.c @@ -0,0 +1,29 @@ +#include "biquad_filter.h" + +struct biquadState filter_make_state(float a0, float a1, float a2, + float b1, float b2) { + struct biquadState state = { + .delayed = {0,0}, + .a0 = a0, + .a1 = a1, + .a2 = a2, + .b1 = b1, + .b2 = b2 + }; + return state; +} + +// http://www.earlevel.com/main/2003/02/28/biquads/ +// Direct form II +float biquad_execute(struct biquadState* state, float new_input) { + float left_sum = new_input - + (state->delayed[0] * state->b1) - + (state->delayed[1] * state->b2); + float output = (left_sum * state->a0) + + (state->delayed[0] * state->a1) + + (state->delayed[1] * state->a2); + + state->delayed[1] = state->delayed[0]; + state->delayed[0] = left_sum; + return output; +} \ No newline at end of file diff --git a/quad/src/quad_app/biquad_filter.h b/quad/src/quad_app/biquad_filter.h new file mode 100644 index 0000000000000000000000000000000000000000..a9076573883767901440683df9fe1c45abd52ae7 --- /dev/null +++ b/quad/src/quad_app/biquad_filter.h @@ -0,0 +1,14 @@ +#ifndef BIQUAD_FILTER_H +#define BIQUAD_FILTER_H + +struct biquadState { + float delayed[2]; + float a0, a1, a2, b1, b2; +}; + +float biquad_execute(struct biquadState* state, float new_input); + + +struct biquadState filter_make_state(float a0, float a1, float a2, + float b1, float b2); +#endif // BIQUAD_FILTER_H \ No newline at end of file diff --git a/quad/src/quad_app/callbacks.c b/quad/src/quad_app/callbacks.c index 6ddd546a344df78d637707399cf600472040df53..cb99d83ad9d108e297121666df94159e96fbaedd 100644 --- a/quad/src/quad_app/callbacks.c +++ b/quad/src/quad_app/callbacks.c @@ -1,8 +1,10 @@ #include "communication.h" #include "commands.h" +#include "graph_blocks.h" #include "type_def.h" #include "computation_graph.h" #include "util.h" +#include "graph_blocks.h" /* * Static variables used to keep track of packet counts @@ -16,16 +18,16 @@ static size_t total_payload_received = 0; /** * Currently does nothing. */ -int cb_debug(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) +int cb_debug(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { - char buf[255]; + u8 buf[255]; // Get the node ID, parameter ID, parameter value u8 node_id = data[0]; struct computation_graph* graph = structs->parameter_struct.graph; float param_val = graph_get_output(graph, node_id, 0); - int len = snprintf(buf, sizeof buf, "%f", param_val); + int len = snprintf((char*)buf, sizeof buf, "%f", param_val); send_data(&structs->hardware_struct.uart, DEBUG_ID, 0, buf, len >= sizeof(buf) ? 255 : length + 1); return 0; } @@ -33,9 +35,12 @@ int cb_debug(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) /** * counts the number of packet logs. */ -int cb_packetlog(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { +int cb_packetlog(struct modular_structs* structs, struct metadata *meta, u8 *data, u16 length) { + char buf[64]; n_msg_received += 1; total_payload_received += length; + int len = sprintf(buf, "Packets received: %d", n_msg_received); + send_data(&structs->hardware_struct.uart, PACKETLOG_ID, 0, buf, len); return 0; } @@ -43,11 +48,11 @@ int cb_packetlog(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 len * Handles a get packet logs request and sends a response * with the packet log data. */ -int cb_getpacketlogs(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { +int cb_getpacketlogs(struct modular_structs* structs, struct metadata *meta, u8 *data, u16 length) { char buf[255]; // Message logging number of messages received and size of payload received - int len = snprintf(buf, sizeof buf, "%d,%d", n_msg_received, total_payload_received); + int len = snprintf((char*)buf, sizeof buf, "%d,%lu", n_msg_received, total_payload_received); send_data(&structs->hardware_struct.uart, LOG_ID, 0, buf, len >= sizeof(buf) ? 255 : len + 1); return 0; @@ -56,7 +61,7 @@ int cb_getpacketlogs(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 /* * Handles receiving new location updates. */ -int cb_update(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) +int cb_update(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { //processUpdate(packet, &(structs->raw_sensor_struct.currentQuadPosition)); @@ -94,7 +99,7 @@ int cb_update(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length /** * This is called on the ground station to begin sending VRPN to the quad. */ -int cb_beginupdate(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) { +int cb_beginupdate(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { structs->user_input_struct.receivedBeginUpdate = 1; return 0; } @@ -137,7 +142,7 @@ struct node_ids get_node_ids(u8 *data) { * * Does not send anything in response. */ -int cb_setparam(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) +int cb_setparam(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { // Check if the data length is correct if (length != 8) {return -1;} @@ -176,7 +181,7 @@ int cb_setparam(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 leng * | bytes || 2 | 2 | 4 | * |--------------------------------------------------------| */ -int cb_getparam(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) +int cb_getparam(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { // Check if the data length is correct if (length != 4) {return -1;} @@ -188,7 +193,7 @@ int cb_getparam(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 len float param_val = graph_get_param_val(graph, ids.id, ids.sub_id); // Format the response data - char resp_data[8]; + u8 resp_data[8]; // Controller ID pack_short(ids.id, resp_data); // Parameter ID @@ -199,7 +204,7 @@ int cb_getparam(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 len // Send the response send_data(&structs->hardware_struct.uart, RESPPARAM_ID, msg_id, resp_data, sizeof(resp_data)); - return 0; + return 5; } /** @@ -217,7 +222,7 @@ int cb_getparam(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 len * * Does not send anything in response. */ -int cb_setsource(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { +int cb_setsource(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { if (length != 8) {return -1;} int16_t dest_node = build_short(data); int16_t dest_input = build_short(data + 2); @@ -254,7 +259,7 @@ int cb_setsource(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 le * | bytes || 2 | 2 | 2 | 2 | * |---------------------------------------------------------------------------| */ -int cb_getsource(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { +int cb_getsource(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { if (length != 4) {return -1;} u16 msg_id = meta->msg_id; // Get requested IDs @@ -270,13 +275,14 @@ int cb_getsource(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 le pack_short(source.controller_output, resp_data + 6); send_data(&structs->hardware_struct.uart, RESPSOURCE_ID, msg_id, resp_data, sizeof(resp_data)); + return 0; } /** * Handles a command to get a node output value from the quad. * Packet structure is the same as getparam */ -int cb_getoutput(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) +int cb_getoutput(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { // Check if the data length is correct if (length != 4) {return -1;} @@ -288,7 +294,7 @@ int cb_getoutput(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 le float output_val = graph_get_output(graph, ids.id, ids.sub_id); // Format the response data - char resp_data[8]; + u8 resp_data[8]; // Controller ID pack_short(ids.id, resp_data); // Output ID @@ -315,35 +321,41 @@ int cb_getoutput(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 le * | bytes || 2*N | 2*N | < 4096 | * |---------------------------------------------------------------| */ -int cb_getnodes(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { +int cb_getnodes(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { const struct computation_graph* graph = structs->parameter_struct.graph; if (graph->n_nodes >= 150) { static char* error_msg = "Over 150 nodes. Not responding to cb_getnodes for fear of buffer overflow."; send_data(&structs->hardware_struct.uart, DEBUG_ID, 0, - error_msg, sizeof(error_msg)); + (u8*)error_msg, sizeof(error_msg)); return -1; } // Number of bytes in node ID being sent. Currently short (16 bits) - size_t id_len = 2; + const size_t id_len = 2; + + u8 resp_buf[4096]; + size_t offset = 0; + // Send the number of nodes there are in the graph + pack_short(graph->n_nodes, resp_buf + offset); + offset += id_len; - char resp_buf[4096]; + // Send all the node data int i; // Currently ID is always index in array. // computation_graph provides no method of accessing ID, since it is implicit for (i = 0; i < graph->n_nodes; i++) { - pack_short(i, resp_buf + (id_len * i)); + pack_short(i, resp_buf + offset); + offset += id_len; } // Construct type IDs - size_t offset = id_len * graph->n_nodes; for (i = 0; i < graph->n_nodes; i++) { int type_id = graph->nodes[i].type->type_id; - pack_short(type_id, resp_buf + offset + (id_len * i)); + pack_short(type_id, resp_buf + offset); + offset += id_len; } // Construct list of node names - offset += id_len * graph->n_nodes; for (i = 0; i < graph->n_nodes; i++) { size_t remaining_size = sizeof(resp_buf) - offset; const char* name = graph->nodes[i].name; @@ -381,10 +393,19 @@ int cb_getnodes(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 len * | bytes || 2 | * |-----------------------------| */ -int cb_addnode(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { +int cb_addnode(struct modular_structs *structs, struct metadata *meta, unsigned char *data, unsigned short length) { + // Check if the data length is large enough if (length < 2) {return -1;} - // Size of name - size_t name_len = length - 2; + struct computation_graph* graph = structs->parameter_struct.graph; + // Get the data for the new node + int block_type = build_short(data); + char* name = (char*) &data[2]; + int new_node_id = graph_add_defined_block(graph, block_type, name); + + // Respond with the result of graph_add_defined_block, which will be -1 if failure + u8 resp_buf[2]; + pack_short(new_node_id, resp_buf); + send_data(&structs->hardware_struct.uart, RESPADDNODE_ID, meta->msg_id, resp_buf, sizeof(resp_buf)); return 0; } diff --git a/quad/src/quad_app/callbacks.h b/quad/src/quad_app/callbacks.h index 3a13626dbd13e8c3d5bba48cf6c4675069e96394..7642fd1624fb5563535c2d03b0ea448e4a6ef1c2 100644 --- a/quad/src/quad_app/callbacks.h +++ b/quad/src/quad_app/callbacks.h @@ -1,9 +1,9 @@ #ifndef __callbacks_h #define __callbacks_h +#include "commands.h" /* Grab some stupid stuff from legacy code */ struct modular_structs; -struct metadata; typedef int (command_cb)(struct modular_structs *, struct metadata *, unsigned char *, unsigned short); #endif diff --git a/quad/src/quad_app/communication.c b/quad/src/quad_app/communication.c index c0d37659e29c0b8145b00e15f9a3302e2ef343ae..aa7561a20a2b389a0a21e39cfc585192ce8a61cc 100644 --- a/quad/src/quad_app/communication.c +++ b/quad/src/quad_app/communication.c @@ -22,7 +22,6 @@ u8 packet[MAX_PACKET_SIZE]; int bytes_recv = 0; int try_receive_packet(struct UARTDriver *uart) { - int attempts = 0; while (attempts++ < MAX_PACKET_SIZE) { // Find start of packet @@ -77,7 +76,7 @@ int try_receive_packet(struct UARTDriver *uart) { } int process_packet(modular_structs_t *structs) { - metadata_t meta; + struct metadata meta; // parse metadata meta.begin_char = packet[0]; meta.msg_type = packet[2] << 8 | packet[1]; @@ -103,7 +102,7 @@ void process_received(modular_structs_t *structs) { } } -int send_data(struct UARTDriver *uart, u16 type_id, u16 msg_id, char* data, size_t size) { +int send_data(struct UARTDriver *uart, u16 type_id, u16 msg_id, u8* data, size_t size) { //---------------------------------------------------------------------------------------------- // index|| 0 | 1 | 2 | 3 & 4 | 5 & 6 | 7+ | end | //---------------------------------------------------------------------------------------------| @@ -135,7 +134,7 @@ int send_data(struct UARTDriver *uart, u16 type_id, u16 msg_id, char* data, size } for (i = 0; i < size; i++) { packet_checksum ^= data[i]; - uart->write(uart, (unsigned char) data[i]); + uart->write(uart, data[i]); } uart->write(uart, packet_checksum); diff --git a/quad/src/quad_app/communication.h b/quad/src/quad_app/communication.h index 8655aad007e1406774d1a70cf2ed130faac4f426..6441ef11000c0d644b0f1df2b3b8024f94d080d8 100644 --- a/quad/src/quad_app/communication.h +++ b/quad/src/quad_app/communication.h @@ -10,6 +10,6 @@ int initUartComms(); void process_received(modular_structs_t *structs); -int send_data(struct UARTDriver *uart, u16 type_id, u16 msg_id, char* data, size_t size); +int send_data(struct UARTDriver *uart, u16 type_id, u16 msg_id, u8* data, size_t size); #endif diff --git a/quad/src/quad_app/control_algorithm.c b/quad/src/quad_app/control_algorithm.c index 424f098cbe02be1fb3e7707b6383fa0814c99957..710f26b34144c2827d46aa0363575541a12aae97 100644 --- a/quad/src/quad_app/control_algorithm.c +++ b/quad/src/quad_app/control_algorithm.c @@ -13,15 +13,17 @@ #include "util.h" #include "timer.h" -#define ROLL_PITCH_MAX_ANGLE 1.5708 // 90 degrees -#define PWM_DIFF_BOUNDS 30000 +#define ROLL_PITCH_MAX_ANGLE 0.35 // 20 degrees +#define PWM_DIFF_BOUNDS 20000 #define VRPN_REFRESH_TIME 0.01f // 10ms void connect_autonomous(parameter_t* ps) { struct computation_graph* graph = ps->graph; - graph_set_source(graph, ps->pitch_pid, PID_SETPOINT, ps->x_pos_pid, PID_CORRECTION); - graph_set_source(graph, ps->roll_pid, PID_SETPOINT, ps->y_pos_pid, PID_CORRECTION); - //graph_set_source(graph, ps->mixer, MIXER_THROTTLE, ps->throttle_trim_add, ADD_SUM); + //graph_set_source(graph, ps->pitch_pid, PID_SETPOINT, ps->x_pos_pid, PID_CORRECTION); + //graph_set_source(graph, ps->roll_pid, PID_SETPOINT, ps->y_pos_pid, PID_CORRECTION); + graph_set_source(graph, ps->pitch_pid, PID_SETPOINT, ps->x_vel_pid, PID_CORRECTION); + graph_set_source(graph, ps->roll_pid, PID_SETPOINT, ps->y_vel_pid, PID_CORRECTION); + graph_set_source(graph, ps->mixer, MIXER_THROTTLE, ps->throttle_trim_add, ADD_SUM); graph_set_source(graph, ps->yaw_r_pid, PID_SETPOINT, ps->yaw_pid, PID_CORRECTION); } @@ -59,6 +61,10 @@ int control_algorithm_init(parameter_t * ps) ps->cur_pitch = graph_add_defined_block(graph, BLOCK_CONSTANT, "Pitch"); // ID 15 ps->cur_roll = graph_add_defined_block(graph, BLOCK_CONSTANT, "Roll"); ps->cur_yaw = graph_add_defined_block(graph, BLOCK_CONSTANT, "Yaw"); + // Sensor trims + ps->pitch_trim = graph_add_defined_block(graph, BLOCK_CONSTANT, "Pitch trim"); + ps->pitch_trim_add = graph_add_defined_block(graph, BLOCK_ADD, "Pitch trim add"); + // Yaw angular velocity PID // theta_dot is the angular velocity about the y-axis // phi_dot is the angular velocity about the x-axis @@ -90,10 +96,14 @@ int control_algorithm_init(parameter_t * ps) ps->pos_time = graph_add_defined_block(graph, BLOCK_CONSTANT, "Ts_VRPN"); // Connect pitch PID chain + // Trims + graph_set_source(graph, ps->pitch_trim_add, ADD_SUMMAND1, ps->pitch_trim, CONST_VAL); + graph_set_source(graph, ps->pitch_trim_add, ADD_SUMMAND2, ps->cur_pitch, CONST_VAL); + // Controllers graph_set_source(graph, ps->pitch_r_pid, PID_SETPOINT, ps->pitch_pid, PID_CORRECTION); graph_set_source(graph, ps->pitch_r_pid, PID_CUR_POINT, ps->theta_dot, CONST_VAL); graph_set_source(graph, ps->pitch_r_pid, PID_DT, ps->angle_time, CONST_VAL); - graph_set_source(graph, ps->pitch_pid, PID_CUR_POINT, ps->cur_pitch, CONST_VAL); + graph_set_source(graph, ps->pitch_pid, PID_CUR_POINT, ps->pitch_trim_add, ADD_SUM); //graph_set_source(graph, ps->pitch_pid, PID_CUR_POINT, ps->vrpn_pitch, CONST_VAL); graph_set_source(graph, ps->pitch_pid, PID_DT, ps->angle_time, CONST_VAL); @@ -188,6 +198,60 @@ int control_algorithm_init(parameter_t * ps) graph_set_param_val(graph, ps->clamp_d_pwmY, BOUNDS_MAX, PWM_DIFF_BOUNDS); + // Velocity stuff + int zero_block = graph_add_defined_block(graph, BLOCK_CONSTANT, "zero"); + + ps->x_vel_pid = graph_add_defined_block(graph, BLOCK_PID, "X Vel PID"); + ps->y_vel_pid = graph_add_defined_block(graph, BLOCK_PID, "Y Vel PID"); + ps->x_vel = graph_add_defined_block(graph, BLOCK_PID, "X Vel"); + ps->y_vel = graph_add_defined_block(graph, BLOCK_PID, "Y Vel"); + ps->x_vel_clamp = graph_add_defined_block(graph, BLOCK_BOUNDS, "X Vel Clamp"); + ps->y_vel_clamp = graph_add_defined_block(graph, BLOCK_BOUNDS, "Y vel Clamp"); + ps->vel_x_gain = graph_add_defined_block(graph, BLOCK_GAIN, "X Stick Gain"); + ps->vel_y_gain = graph_add_defined_block(graph, BLOCK_GAIN, "Y Stick Gain"); + + graph_set_source(graph, ps->x_vel_pid, PID_DT, ps->pos_time, CONST_VAL); + graph_set_source(graph, ps->y_vel_pid, PID_DT, ps->pos_time, CONST_VAL); + graph_set_source(graph, ps->x_vel, PID_DT, ps->pos_time, CONST_VAL); + graph_set_source(graph, ps->y_vel, PID_DT, ps->pos_time, CONST_VAL); + + graph_set_source(graph, ps->x_vel_pid, PID_SETPOINT, ps->x_vel, PID_CORRECTION); + graph_set_source(graph, ps->y_vel_pid, PID_SETPOINT, ps->y_vel, PID_CORRECTION); + graph_set_source(graph, ps->x_vel_pid, PID_CUR_POINT, ps->x_vel, PID_CORRECTION); + graph_set_source(graph, ps->y_vel_pid, PID_CUR_POINT, ps->y_vel, PID_CORRECTION); + + graph_set_source(graph, ps->x_vel, PID_CUR_POINT, ps->vrpn_x, CONST_VAL); + graph_set_source(graph, ps->y_vel, PID_CUR_POINT, ps->vrpn_y, CONST_VAL); + graph_set_source(graph, ps->x_vel, PID_SETPOINT, zero_block, CONST_VAL); + graph_set_source(graph, ps->y_vel, PID_SETPOINT, zero_block, CONST_VAL); + + graph_set_source(graph, ps->x_vel_pid, PID_SETPOINT, ps->x_vel_clamp, GAIN_RESULT); + graph_set_source(graph, ps->y_vel_pid, PID_SETPOINT, ps->y_vel_clamp, GAIN_RESULT); + + graph_set_source(graph, ps->x_vel_clamp, BOUNDS_IN, ps->x_pos_pid, PID_CORRECTION); + graph_set_source(graph, ps->y_vel_clamp, BOUNDS_IN, ps->y_pos_pid, PID_CORRECTION); + //graph_set_source(graph, ps->vel_x_gain, GAIN_INPUT, ps->rc_pitch, CONST_VAL); + //graph_set_source(graph, ps->vel_y_gain, GAIN_INPUT, ps->rc_roll, CONST_VAL); + //graph_set_source(graph, ps->x_vel_clamp, BOUNDS_IN, ps->vel_x_gain, GAIN_RESULT); + //graph_set_source(graph, ps->y_vel_clamp, BOUNDS_IN, ps->vel_y_gain, GAIN_RESULT); + + float vel_clamps = 2; + graph_set_param_val(graph, ps->x_vel_clamp, BOUNDS_MIN, -vel_clamps); + graph_set_param_val(graph, ps->x_vel_clamp, BOUNDS_MAX, vel_clamps); + graph_set_param_val(graph, ps->y_vel_clamp, BOUNDS_MIN, -vel_clamps); + graph_set_param_val(graph, ps->y_vel_clamp, BOUNDS_MAX, vel_clamps); + + + graph_set_param_val(graph, ps->x_vel, PID_KD, 1); + graph_set_param_val(graph, ps->y_vel, PID_KD, 1); + + graph_set_param_val(graph, ps->vel_x_gain, GAIN_GAIN, 5); + graph_set_param_val(graph, ps->vel_y_gain, GAIN_GAIN, -5); + + + // Set trims + graph_set_param_val(graph, ps->pitch_trim, CONST_SET, 0.02); + // Initial value for sampling periods graph_set_param_val(graph, ps->pos_time, CONST_SET, 0.04); graph_set_param_val(graph, ps->angle_time, CONST_SET, 0.005); diff --git a/quad/src/quad_app/controllers.h b/quad/src/quad_app/controllers.h index 33b6237957b49d4253c3fec7c26b917cdfe3f74e..1e12c7590e5fe661b81a1bca31b7398da3e457d3 100644 --- a/quad/src/quad_app/controllers.h +++ b/quad/src/quad_app/controllers.h @@ -102,6 +102,9 @@ #define min 100000 #define max 200000 +#define MOTOR_MIN 100000 +#define MOTOR_MAX 200000 + void filter_PWMs(int* mixer); void PWMS_to_Aero(int* PWMs, int* aero); // <= javey: unused void Aero_to_PWMS(int* PWMs, int* aero); diff --git a/quad/src/quad_app/hw_iface.h b/quad/src/quad_app/hw_iface.h index bbd6bb6fc14171d0f506151a1b87bffb9b869b21..bde0aa3f8170f465e8ab33be4576804850abfee8 100644 --- a/quad/src/quad_app/hw_iface.h +++ b/quad/src/quad_app/hw_iface.h @@ -1,6 +1,20 @@ #ifndef HW_IFACE_H #define HW_IFACE_H +/** + * Hardware Interfaces + * + * These interfaces are used to accomplish separation between the application + * layer and the hardware layer in the program that runs on the quadcopter. + * + * NOTE: + * If you wound up here after following some IDE function declaration trail, + * you've hit the end of the application layer. Go to the location of the + * hardware layer appropriate for your circumstance:p + * ../../xsdk_worksapce/modular_quad_pid -> running quad_app on the Zybo + * ../virt_quad -> running quad_app in a Unix environment + */ + struct I2CDriver { void *state; int (*reset)(struct I2CDriver *self); diff --git a/quad/src/quad_app/iic_utils.c b/quad/src/quad_app/iic_utils.c index 90cdfb6872963b2c3ef5c7437a8abb9435e0c581..a9fbd272c723f5a81942a9edef2adcf7dae613fb 100644 --- a/quad/src/quad_app/iic_utils.c +++ b/quad/src/quad_app/iic_utils.c @@ -30,7 +30,7 @@ int iic0_mpu9150_start(){ // Set clock reference to Z Gyro iic0_mpu9150_write(0x6B, 0x03); // Configure Digital Low/High Pass filter - iic0_mpu9150_write(0x1A,0x06); // Level 6 low pass on gyroscope + iic0_mpu9150_write(0x1A,0x03); // Level 3 low pass on gyroscope // Configure Gyro to 2000dps, Accel. to +/-8G iic0_mpu9150_write(0x1B, 0x18); @@ -182,10 +182,6 @@ int iic0_mpu9150_read_gam(gam_t* gam) { gam->accel_y = (raw_accel_y / 4096.0) + ACCEL_Y_BIAS; gam->accel_z = (raw_accel_z / 4096.0) + ACCEL_Z_BIAS; - //Get X and Y angles - // javey: this assigns accel_(pitch/roll) in units of radians - gam->accel_pitch = atan(gam->accel_x / sqrt(gam->accel_y*gam->accel_y + gam->accel_z*gam->accel_z)); - gam->accel_roll = -atan(gam->accel_y / sqrt(gam->accel_x*gam->accel_x + gam->accel_z*gam->accel_z)); // negative because sensor board is upside down //Convert gyro data to rate (we're only using the most 12 significant bits) gyro_x = (sensor_data[GYR_X_H] << 8) | (sensor_data[GYR_X_L]); //* G_GAIN; diff --git a/quad/src/quad_app/initialize_components.c b/quad/src/quad_app/initialize_components.c index 858c0e9ffb80525c72c04726698a98eac45b518f..967eaa6294b342641fc1dcdfb0b3327ea4490427 100644 --- a/quad/src/quad_app/initialize_components.c +++ b/quad/src/quad_app/initialize_components.c @@ -7,6 +7,7 @@ #include "initialize_components.h" #include "communication.h" +#include "controllers.h" #include "sensor.h" #include "iic_utils.h" @@ -83,6 +84,12 @@ int init_structs(modular_structs_t *structs) { struct PWMOutputDriver *pwm_outputs = &structs->hardware_struct.pwm_outputs; if (pwm_outputs->reset(pwm_outputs)) return -1; + // Set motor outputs to off + int i; + for (i = 0; i < 4; i += 1) { + pwm_outputs->write(pwm_outputs, i, MOTOR_MIN); + } + // Initialize sensors //manual flight mode @@ -92,5 +99,7 @@ int init_structs(modular_structs_t *structs) { if(sensor_init(&structs->raw_sensor_struct, &structs->sensor_struct) == -1) return -1; + sensor_processing_init(&structs->sensor_struct); + return 0; } diff --git a/quad/src/quad_app/log_data.c b/quad/src/quad_app/log_data.c index 4ad8410b526249d0499b33095a249183e187df04..e67a075394ee6099d89f0c326a07f656a72694ee 100644 --- a/quad/src/quad_app/log_data.c +++ b/quad/src/quad_app/log_data.c @@ -17,9 +17,9 @@ #include "graph_blocks.h" // Current index of the log array -int arrayIndex = 0; +static int arrayIndex = 0; // Size of the array -int arraySize = 0; +static int arraySize = 0; struct graph_tuple { // Tuple for int block_id; @@ -42,11 +42,11 @@ struct str { struct graph_tuple log_outputs[MAX_LOG_NUM]; struct graph_tuple log_params[MAX_LOG_NUM]; -size_t n_outputs; -size_t n_params; +static size_t n_outputs; +static size_t n_params; -float* logArray = NULL; -int row_size; +static float* logArray = NULL; +static int row_size; static char units_output_str[512] = {}; static char units_param_str[512] = {}; @@ -95,6 +95,7 @@ void initialize_logging(log_t* log_struct, parameter_t* ps) { char* rad_s = "rad/s"; char* pwm_val = "10ns_dutycycle"; char* m = "m"; + char* m_s = "m/s"; addOutputToLog(log_struct, ps->alt_pid, PID_CORRECTION, pwm_val); addOutputToLog(log_struct, ps->x_pos_pid, PID_CORRECTION, rad); addOutputToLog(log_struct, ps->y_pos_pid, PID_CORRECTION, rad); @@ -104,7 +105,7 @@ void initialize_logging(log_t* log_struct, parameter_t* ps) { addOutputToLog(log_struct, ps->pitch_r_pid, PID_CORRECTION, pwm_val); addOutputToLog(log_struct, ps->roll_r_pid, PID_CORRECTION, pwm_val); addOutputToLog(log_struct, ps->yaw_r_pid, PID_CORRECTION, pwm_val); - addOutputToLog(log_struct, ps->cur_pitch, CONST_VAL, rad); + addOutputToLog(log_struct, ps->pitch_trim_add, CONST_VAL, rad); addOutputToLog(log_struct, ps->cur_roll, CONST_VAL, rad); addOutputToLog(log_struct, ps->cur_yaw, CONST_VAL, rad); addOutputToLog(log_struct, ps->vrpn_x, CONST_VAL, m); @@ -115,11 +116,17 @@ void initialize_logging(log_t* log_struct, parameter_t* ps) { addOutputToLog(log_struct, ps->x_set, CONST_VAL, m); addOutputToLog(log_struct, ps->y_set, CONST_VAL, m); addOutputToLog(log_struct, ps->alt_set, CONST_VAL, m); - addOutputToLog(log_struct, ps->yaw_set, CONST_VAL, rad); addOutputToLog(log_struct, ps->mixer, MIXER_PWM0, pwm_val); addOutputToLog(log_struct, ps->mixer, MIXER_PWM1, pwm_val); addOutputToLog(log_struct, ps->mixer, MIXER_PWM2, pwm_val); addOutputToLog(log_struct, ps->mixer, MIXER_PWM3, pwm_val); + addOutputToLog(log_struct, ps->rc_throttle, PID_CORRECTION, pwm_val); + addOutputToLog(log_struct, ps->rc_pitch, PID_CORRECTION, pwm_val); + addOutputToLog(log_struct, ps->rc_roll, PID_CORRECTION, pwm_val); + addOutputToLog(log_struct, ps->x_vel_pid, PID_CORRECTION, rad); + addOutputToLog(log_struct, ps->y_vel_pid, PID_CORRECTION, rad); + addOutputToLog(log_struct, ps->x_vel, PID_CORRECTION, m_s); + addOutputToLog(log_struct, ps->y_vel, PID_CORRECTION, m_s); // TODO: Make this not stupid. Adding 6 for IMU and 1 for timestamp row_size = n_outputs + n_params + 6 + 1; @@ -139,7 +146,7 @@ int log_data(log_t* log_struct, parameter_t* ps) { return 1; } - float* thisRow = &logArray[arrayIndex * row_size * sizeof(float)]; + float* thisRow = &logArray[arrayIndex * row_size]; int offset = 0; thisRow[offset++] = log_struct->time_stamp; thisRow[offset++] = log_struct->gam.accel_x; @@ -182,12 +189,27 @@ void printLogging(hardware_t *hardware_struct, log_t* log_struct, parameter_t* p send_data(&hardware_struct->uart, LOG_ID, 0, buf.str, buf.size); return; } + + int i; // Comment header safe_sprintf_cat(&buf, "# MicroCART On-board Quad Log\n# Sample size: %d\n", arrayIndex); + + // List Pid Constants + for (i = 0; i < ps->graph->n_nodes; ++i) { + struct graph_node* node = &ps->graph->nodes[i]; + if (node->type->type_id == BLOCK_PID) { + double kp, ki, kd; + kp = graph_get_param_val(ps->graph, i, 0); + ki = graph_get_param_val(ps->graph, i, 1); + kd = graph_get_param_val(ps->graph, i, 2); + safe_sprintf_cat(&buf, "# %s :\tKp = %lf Ki = %lf Kd = %lf\n", node->name, kp, ki, kd); + + } + } + // Header names for the pre-defined values - safe_sprintf_cat(&buf, "%Time\taccel_x\taccel_y\taccel_z\tgyro_x\tgyro_y\tgyro_z"); + safe_sprintf_cat(&buf, "%%Time\taccel_x\taccel_y\taccel_z\tgyro_x\tgyro_y\tgyro_z"); - int i; // Print all the recorded block parameters for (i = 0; i < n_params; i++) { const char* block_name = ps->graph->nodes[log_params[i].block_id].name; @@ -235,7 +257,7 @@ void format_log(int idx, log_t* log_struct, struct str* buf) { int i; buf->size = 0; - float* row = &logArray[idx * row_size * sizeof(float)];\ + float* row = &logArray[idx * row_size];\ safe_sprintf_cat(buf, "%f", row[0]); for (i = 1; i < row_size; i++) { diff --git a/quad/src/quad_app/log_data.h b/quad/src/quad_app/log_data.h index 34f1658d02f316918547bc0eedd760bcbf121264..becc2c2e188a819e1e9735cc625e93dd514f52c7 100644 --- a/quad/src/quad_app/log_data.h +++ b/quad/src/quad_app/log_data.h @@ -9,7 +9,7 @@ #define LOG_DATA_H_ #include "type_def.h" -#define LOG_STARTING_SIZE 8192 //262144 // 2^18 32768 2^15 +#define LOG_STARTING_SIZE 60000 //262144 // 2^18 32768 2^15 // Maximum number of block outputs you can record, and maximum number of block parameters to record #define MAX_LOG_NUM 50 diff --git a/quad/src/quad_app/quad_app.c b/quad/src/quad_app/quad_app.c index 22829b5c8d2a6e5247a670f348c4ecad03dc6473..01eabe9017f733685ae8f9737398099e657a0bf0 100644 --- a/quad/src/quad_app/quad_app.c +++ b/quad/src/quad_app/quad_app.c @@ -18,9 +18,6 @@ #include "communication.h" #include "mio7_led.h" -//#define BENCH_TEST -//#define UART_BENCHMARK - int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)) { // Structures to be used throughout @@ -38,10 +35,8 @@ int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)) return -1; } -#ifndef BENCH_TEST // Loops to make sure the quad is responding correctly before starting the control loop protection_loops(&structs); -#endif int last_kill_condition = kill_condition(&(structs.user_input_struct)); @@ -55,24 +50,8 @@ int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)) // Process all received data -#ifdef UART_BENCHMARK - usleep(500000); - u32 start_time = timer_get_count(); -#endif - process_received(&structs); -#ifdef UART_BENCHMARK - u32 end_time = timer_get_count(); - u32 duration = end_time - start_time; - u32 packets_processed = uart_buff_packets_processed(); - u32 data[2]; - data[0] = duration; - data[1] = packets_processed; - send_data(0, 0, 0, (char *) &data, 8); -#endif - -#ifndef BENCH_TEST // Get the user input and put it into user_input_struct get_user_input(&(structs.hardware_struct), &(structs.log_struct), &(structs.user_input_struct)); @@ -95,16 +74,13 @@ int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)) } // update the GUI update_GUI(&(structs.log_struct)); -#endif - // Processing of loop timer at the end of the control loop - timer_end_loop(&(structs.log_struct)); if (!this_kill_condition) { + // Log the data collected in this loop + log_data(&(structs.log_struct), &(structs.parameter_struct)); + if(structs.user_defined_struct.flight_mode == AUTO_FLIGHT_MODE) { - // Log the data collected in this loop - log_data(&(structs.log_struct), &(structs.parameter_struct)); - static int loop_counter = 0; loop_counter++; @@ -134,6 +110,9 @@ int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)) } last_kill_condition = this_kill_condition; + + // Processing of loop timer at the end of the control loop + timer_end_loop(&(structs.log_struct)); } kill_motors(&(structs.hardware_struct.pwm_outputs)); diff --git a/quad/src/quad_app/sensor_processing.c b/quad/src/quad_app/sensor_processing.c index d7bd7b707ac23b2b87e8c5aab8029840dce80b31..3e3b48bd1bbcb16dca49f198494ce05f847b6dfd 100644 --- a/quad/src/quad_app/sensor_processing.c +++ b/quad/src/quad_app/sensor_processing.c @@ -14,8 +14,33 @@ #include "timer.h" #include <math.h> +#define ALPHA 0.99 + +int sensor_processing_init(sensor_t* sensor_struct) { + float a0 = 0.0200833310260; + float a1 = 0.0401666620520; + float a2 = 0.0200833310260; + float b1 = -1.561015391253; + float b2 = 0.6413487153577; + sensor_struct->accel_x_filt = filter_make_state(a0, a1, a2, b1, b2); + sensor_struct->accel_y_filt = filter_make_state(a0, a1, a2, b1, b2); + sensor_struct->accel_z_filt = filter_make_state(a0, a1, a2, b1, b2); + return 0; +} + int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_sensor_t* raw_sensor_struct, sensor_t* sensor_struct) { + // Filter accelerometer values + gam_t* gam = &(raw_sensor_struct->gam); + float accel_x = biquad_execute(&sensor_struct->accel_x_filt, gam->accel_x); + float accel_y = biquad_execute(&sensor_struct->accel_y_filt, gam->accel_y); + float accel_z = biquad_execute(&sensor_struct->accel_z_filt, gam->accel_z); + //Get X and Y angles + // javey: this assigns accel_(pitch/roll) in units of radians + float accel_pitch = atan(accel_x / sqrt(accel_y*accel_y + accel_z*accel_z)); + float accel_roll = -atan(accel_y / sqrt(accel_x*accel_x + accel_z*accel_z)); // negative because sensor board is upside down + + // copy currentQuadPosition and trimmedRCValues from raw_sensor_struct to sensor_struct deep_copy_Qpos(&(sensor_struct->currentQuadPosition), &(raw_sensor_struct->currentQuadPosition)); @@ -31,13 +56,14 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se // |local y| = |sin(yaw angle) cos(yaw angle) 0| |camera given y| // |local z| | 0 0 1| |camera given z| + sensor_struct->currentQuadPosition.x_pos = - sensor_struct->currentQuadPosition.x_pos * cos(sensor_struct->currentQuadPosition.yaw) + - sensor_struct->currentQuadPosition.y_pos * -sin(sensor_struct->currentQuadPosition.yaw); + raw_sensor_struct->currentQuadPosition.x_pos * cos(raw_sensor_struct->currentQuadPosition.yaw) + + raw_sensor_struct->currentQuadPosition.y_pos * -sin(raw_sensor_struct->currentQuadPosition.yaw); sensor_struct->currentQuadPosition.y_pos = - sensor_struct->currentQuadPosition.x_pos * sin(sensor_struct->currentQuadPosition.yaw) + - sensor_struct->currentQuadPosition.y_pos * cos(sensor_struct->currentQuadPosition.yaw); + raw_sensor_struct->currentQuadPosition.x_pos * sin(raw_sensor_struct->currentQuadPosition.yaw) + + raw_sensor_struct->currentQuadPosition.y_pos * cos(raw_sensor_struct->currentQuadPosition.yaw); // Calculate Euler angles and velocities using Gimbal Equations below @@ -85,11 +111,11 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se sensor_struct->gyr_z = raw_sensor_struct->gam.gyro_zVel_r; // Complementary Filter Calculations - sensor_struct->pitch_angle_filtered = 0.98 * (sensor_struct->pitch_angle_filtered + sensor_struct->theta_dot * get_last_loop_time()) - + 0.02 * raw_sensor_struct->gam.accel_pitch; + sensor_struct->pitch_angle_filtered = ALPHA * (sensor_struct->pitch_angle_filtered + sensor_struct->theta_dot * get_last_loop_time()) + + (1. - ALPHA) * accel_pitch; - sensor_struct->roll_angle_filtered = 0.98 * (sensor_struct->roll_angle_filtered + sensor_struct->phi_dot* get_last_loop_time()) - + 0.02 * raw_sensor_struct->gam.accel_roll; + sensor_struct->roll_angle_filtered = ALPHA * (sensor_struct->roll_angle_filtered + sensor_struct->phi_dot* get_last_loop_time()) + + (1. - ALPHA) * accel_roll; // static int loop_counter = 0; // loop_counter++; diff --git a/quad/src/quad_app/sensor_processing.h b/quad/src/quad_app/sensor_processing.h index 04b5efebe48ab20bdecfcfaab11e1ffe2f63a540..52b626eafa173ac5c806ad29d52ca03138017060 100644 --- a/quad/src/quad_app/sensor_processing.h +++ b/quad/src/quad_app/sensor_processing.h @@ -77,6 +77,7 @@ */ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_sensor_t * raw_sensor_struct, sensor_t* sensor_struct); +int sensor_processing_init(sensor_t* sensor_struct); void deep_copy_Qpos(quadPosition_t * dest, quadPosition_t * src); void set_pitch_angle_filtered(sensor_t * sensor_struct, float accel_roll); void set_roll_angle_filtered(sensor_t * sensor_struct, float accel_roll); diff --git a/quad/src/quad_app/type_def.h b/quad/src/quad_app/type_def.h index 8d6363cfa70c9eeff3bb0aa8dbac7cafefd466a1..d016134432b8e058601904a5013a296b7ecd7b00 100644 --- a/quad/src/quad_app/type_def.h +++ b/quad/src/quad_app/type_def.h @@ -12,6 +12,7 @@ #include "commands.h" #include "computation_graph.h" #include "hw_iface.h" +#include "biquad_filter.h" typedef unsigned char u8; typedef unsigned short u16; @@ -38,13 +39,6 @@ enum flight_mode{ //-------------------------------------------------------------------------------------------- | // bytes|| 1 | 2 | 2 | 2 | var | 1 | //---------------------------------------------------------------------------------------------- -typedef struct { - char begin_char; - uint16_t msg_type; - uint16_t msg_id; - uint16_t data_len; -} metadata_t; - typedef struct { char** tokens; @@ -285,6 +279,10 @@ typedef struct sensor { quadPosition_t currentQuadPosition; quadTrims_t trims; + struct biquadState accel_x_filt; + struct biquadState accel_y_filt; + struct biquadState accel_z_filt; + } sensor_t; /** @@ -348,6 +346,17 @@ typedef struct parameter_t { // "trim" for autonomous int throttle_trim; int throttle_trim_add; + int pitch_trim; + int pitch_trim_add; + // Velocity nodes + int x_vel_pid; + int y_vel_pid; + int x_vel; + int y_vel; + int x_vel_clamp; + int y_vel_clamp; + int vel_x_gain; + int vel_y_gain; } parameter_t; /** diff --git a/quad/src/quad_app/util.c b/quad/src/quad_app/util.c index c021fef37cc1daeb6adafe20a75b25e1ec99e558..2f1512a0e407385648f442083b2e5152b3fa8dac 100644 --- a/quad/src/quad_app/util.c +++ b/quad/src/quad_app/util.c @@ -68,10 +68,10 @@ int read_flap(int flap) * Turns off the motors */ void kill_motors(struct PWMOutputDriver *pwm_outputs) { - pwm_outputs->write(pwm_outputs, 0, 0); - pwm_outputs->write(pwm_outputs, 1, 0); - pwm_outputs->write(pwm_outputs, 2, 0); - pwm_outputs->write(pwm_outputs, 3, 0); + pwm_outputs->write(pwm_outputs, 0, MOTOR_MIN); + pwm_outputs->write(pwm_outputs, 1, MOTOR_MIN); + pwm_outputs->write(pwm_outputs, 2, MOTOR_MIN); + pwm_outputs->write(pwm_outputs, 3, MOTOR_MIN); } int build_int(u8 *buff) { diff --git a/quad/src/virt_quad/Makefile b/quad/src/virt_quad/Makefile index 3626790b07efec7ea75a039491b6078a8c6918df..acf6d27cbbea07d639fadfda691a01d6edd89fb7 100644 --- a/quad/src/virt_quad/Makefile +++ b/quad/src/virt_quad/Makefile @@ -1,6 +1,8 @@ TOP=../.. -NAME = virt_quad -REQLIBS = -lquad_app -lcomputation_graph -lm -lcommands -lgraph_blocks +NAME = virt-quad +REQLIBS = -Wl,--whole-archive -lquad_app -Wl,--no-whole-archive -lcommands -lgraph_blocks -lcomputation_graph -lm -lpthread include $(TOP)/executable.mk + +CLEANUP += virt-quad-fifos diff --git a/quad/src/virt_quad/README.md b/quad/src/virt_quad/README.md new file mode 100644 index 0000000000000000000000000000000000000000..3607ec44cadba0f318a6797a296b35a8f687c091 --- /dev/null +++ b/quad/src/virt_quad/README.md @@ -0,0 +1,24 @@ +The Virtual Quadcopter +---- +Look at how modular our quad is ... it can even run in a Unix environment! + +But really, this isn't just some token project, this is pretty useful for +debugging routine things in the quad_app without having to fire up the +plethoria of things required for flight in Coover 3050. In fact, you don't +even have to be in Coover 3050... + +# Using the Virtual Quad +Start it up: +``` +make run +``` + +And you can do things with it. You'll notice it will make a bunch of FIFOs in +the current directory. Write to / read from these FIFOs as you see fit. + +## Writing to FIFO from shell + +``` +echo "170000" > virt-quad-fifos/pwm-input-gear # Setting the gear to '1' +cat virt-quad-fifos/pwm-output-motor1 # Read the motor 1 pwm signal +``` \ No newline at end of file diff --git a/quad/src/virt_quad/hw_impl_unix.h b/quad/src/virt_quad/hw_impl_unix.h index c7e3659dffcfb0b1094c26f41ffe3b4d792962b8..38745899342bb3a8c81734bead570d1d876f4cff 100644 --- a/quad/src/virt_quad/hw_impl_unix.h +++ b/quad/src/virt_quad/hw_impl_unix.h @@ -10,6 +10,8 @@ #include <stdlib.h> #include <time.h> +#define VIRT_QUAD_FIFOS_DIR "virt-quad-fifos" + int unix_uart_reset(struct UARTDriver *self); int unix_uart_write(struct UARTDriver *self, unsigned char c); int unix_uart_read(struct UARTDriver *self, unsigned char *c); diff --git a/quad/src/virt_quad/hw_impl_unix_global_timer.c b/quad/src/virt_quad/hw_impl_unix_global_timer.c index be752b774eb55cb17f3c481947f44b76fc2ec124..dc3513d8036b102de55d0c1d90c866ebce86534c 100644 --- a/quad/src/virt_quad/hw_impl_unix_global_timer.c +++ b/quad/src/virt_quad/hw_impl_unix_global_timer.c @@ -4,6 +4,9 @@ int unix_global_timer_reset(struct TimerDriver *self) { if (self->state == NULL) { self->state = malloc(sizeof(struct timeval)); } + struct timezone tz; + struct timeval *start = self->state; + gettimeofday(start, &tz); return 0; } diff --git a/quad/src/virt_quad/hw_impl_unix_i2c.c b/quad/src/virt_quad/hw_impl_unix_i2c.c index 09ab43c8b83b82d60dff7623a31efb1d29c3fd60..97228f0bada9ca366f30c145f66c54edae0cedde 100644 --- a/quad/src/virt_quad/hw_impl_unix_i2c.c +++ b/quad/src/virt_quad/hw_impl_unix_i2c.c @@ -1,6 +1,55 @@ #include "hw_impl_unix.h" +#include <sys/types.h> +#include <sys/stat.h> +#include <fcntl.h> +#include <pthread.h> +#include "iic_utils.h" + +#define NUM_INPUTS 7 + +void * update_i2c_input_cache(void *); + +union val { + unsigned char b[2]; + unsigned short s; +}; + +static char *input_names[NUM_INPUTS]; +static int fifos[NUM_INPUTS]; +static union val cache[NUM_INPUTS]; + +static short last_dev; +static short last_reg; +static short last_val; + +static int nums[] = {0, 1, 2, 3, 4, 5}; +static pthread_t workers[NUM_INPUTS]; int unix_i2c_reset(struct I2CDriver *self) { + input_names[0] = "i2c-mpu-accel-x"; + input_names[1] = "i2c-mpu-accel-y"; + input_names[2] = "i2c-mpu-accel-z"; + input_names[3] = "i2c-mpu-gryo-x"; + input_names[4] = "i2c-mpu-gryo-y"; + input_names[5] = "i2c-mpu-gyro-z"; + input_names[6] = "i2c-lidar"; + + mkdir(VIRT_QUAD_FIFOS_DIR, 0777); + + // Start up worker thread whose job is to update the caches + int i; + for (i = 0; i < NUM_INPUTS; i += 1) { + pthread_create(&workers[i], 0, update_i2c_input_cache, &nums[i]); + } + + cache[0].s = 0; + cache[1].s = 0; + cache[2].s = 0; + cache[3].s = 0; + cache[4].s = 0; + cache[5].s = 0; + cache[6].s = 0; + return 0; } @@ -8,6 +57,11 @@ int unix_i2c_write(struct I2CDriver *self, unsigned short device_addr, unsigned char *data, unsigned int length) { + if (length == 2) { + last_dev = device_addr; + last_reg = data[0]; + last_val = data[1]; + } return 0; } @@ -15,5 +69,61 @@ int unix_i2c_read(struct I2CDriver *self, unsigned short device_addr, unsigned char *buff, unsigned int length) { + if (last_dev != device_addr) { + return -1; + } + + switch (device_addr) { + case MPU9150_DEVICE_ADDR: + if (last_reg == ACCEL_GYRO_BASE_ADDR) { + buff[0] = cache[0].b[0]; + buff[1] = cache[0].b[1]; + buff[2] = cache[1].b[0]; + buff[3] = cache[1].b[1]; + buff[4] = cache[2].b[0]; + buff[5] = cache[2].b[1]; + buff[6] = 0; + buff[7] = 0; + buff[8] = cache[3].b[0]; + buff[9] = cache[3].b[1]; + buff[10] = cache[4].b[0]; + buff[11] = cache[4].b[1]; + buff[12] = cache[5].b[0]; + buff[13] = cache[5].b[1]; + } + else if (last_reg == LIDARLITE_DEVICE_ADDR) { + buff[0] = cache[6].b[0]; + buff[1] = cache[6].b[0]; + } + else { + return -1; + } + } return 0; } + +void * update_i2c_input_cache(void *arg) { + int *cache_index = arg; + int i = *cache_index; + char buff[16]; + + // Setup FIFO + unlink(input_names[i]); + char fifoname[64]; + sprintf(fifoname, "%s/%s", VIRT_QUAD_FIFOS_DIR, input_names[i]); + mkfifo(fifoname, 0666); + fifos[i] = open(fifoname, O_RDONLY); + + // Block while waiting for reads + while (1) { + int bytes_read = read(fifos[i], buff, 15); + if (bytes_read > 0) { + buff[bytes_read] = '\0'; + unsigned long val = strtoll(buff, NULL, 10); + cache[i].s = val; + printf("%s: %ld\n", input_names[i], val); + } + pthread_yield(); + } + return NULL; +} diff --git a/quad/src/virt_quad/hw_impl_unix_mio7_led.c b/quad/src/virt_quad/hw_impl_unix_mio7_led.c index f96fda029e0c0a9664be8bd81e76a93af606e7ba..b9b66dd09d0725936a97fc86563fb709693b2416 100644 --- a/quad/src/virt_quad/hw_impl_unix_mio7_led.c +++ b/quad/src/virt_quad/hw_impl_unix_mio7_led.c @@ -1,8 +1,31 @@ #include "hw_impl_unix.h" +#include <sys/types.h> +#include <sys/stat.h> +#include <fcntl.h> +#include <string.h> +#include <pthread.h> +#include <unistd.h> +#include <pthread.h> + +void * output_cached_led(); int on; +static char *led_fifo_name; +pthread_t worker; int unix_mio7_led_reset(struct LEDDriver *self) { + led_fifo_name = VIRT_QUAD_FIFOS_DIR "/mio7-led"; + + mkdir(VIRT_QUAD_FIFOS_DIR, 0777); + int i; + for (i = 0; i < 4; i += 1) { + unlink(led_fifo_name); + mkfifo(led_fifo_name, 0666); + } + + // Start up worker thread whose job is to update the caches + pthread_create(&worker, 0, output_cached_led, NULL); + return 0; } @@ -21,3 +44,14 @@ int unix_mio7_led_turn_off(struct LEDDriver *self) { } return 0; } + +void * output_cached_led() { + char buff[16]; + while (1) { + int fifo = open(led_fifo_name, O_WRONLY); + sprintf(buff, "%d\n", on); + write(fifo, buff, strlen(buff)); + close(fifo); + pthread_yield(); + } +} diff --git a/quad/src/virt_quad/hw_impl_unix_pwm_input.c b/quad/src/virt_quad/hw_impl_unix_pwm_input.c index 8881f5f3815f063fb2ce365a6b07c79d7a2eaf44..df1aaf5f9b43811a4af9b5ed73aebe5e0ca24a86 100644 --- a/quad/src/virt_quad/hw_impl_unix_pwm_input.c +++ b/quad/src/virt_quad/hw_impl_unix_pwm_input.c @@ -1,50 +1,84 @@ #include "hw_impl_unix.h" +#include "controllers.h" +#include <sys/types.h> +#include <sys/stat.h> +#include <fcntl.h> +#include <pthread.h> + +void * update_input_cache(); + +static char *input_names[6]; +static int fifos[6]; +static unsigned long cache[6]; +static pthread_t workers[6]; +static int nums[] = {0, 1, 2, 3, 4, 5}; int unix_pwm_input_reset(struct PWMInputDriver *self) { + input_names[0] = "pwm-input-throttle"; + input_names[1] = "pwm-input-roll"; + input_names[2] = "pwm-input-pitch"; + input_names[3] = "pwm-input-yaw"; + input_names[4] = "pwm-input-gear"; + input_names[5] = "pwm-input-flap"; + + mkdir(VIRT_QUAD_FIFOS_DIR, 0777); + + // Start up worker thread whose job is to update the caches + int i; + for (i = 0; i < 6; i += 1) { + pthread_create(&workers[i], 0, update_input_cache, &nums[i]); + usleep(1000); + } + + cache[0] = THROTTLE_MIN; + cache[1] = ROLL_CENTER; + cache[2] = PITCH_CENTER; + cache[3] = YAW_CENTER; + cache[4] = GEAR_0; + cache[5] = FLAP_1; + + for (i = 0; i < 6; i += 1) { + printf("%s: %lu\n", input_names[i], cache[i]); + } + return 0; } int unix_pwm_input_read(struct PWMInputDriver *self, unsigned int channel, unsigned long *pulse_width_us) { - static int inc = 0; - unsigned long gear; - - switch (channel) { - case 0: - *pulse_width_us = 100000; - break; - case 1: - *pulse_width_us = 100000; - break; - case 2: - *pulse_width_us = 100000; - break; - case 3: - *pulse_width_us = 100000; - break; - case 4: - if (inc == 0) { - inc += 1; - puts("GEAR OFF"); - } - if (inc < 20) { - inc += 1; - gear = 120000; - } - else if (inc == 20) { - puts("GEAR ON"); - inc += 1; - } - else { - gear = 140000; + + *pulse_width_us = cache[channel]; + return 0; +} + +void * update_input_cache(void *arg) { + int *cache_index = arg; + int i = *cache_index; + char buff[16]; + + // Setup FIFO + unlink(input_names[i]); + char fifoname[64]; + sprintf(fifoname, "%s/%s", VIRT_QUAD_FIFOS_DIR, input_names[i]); + mkfifo(fifoname, 0666); + fifos[i] = open(fifoname, O_RDONLY); + + // Block while waiting for reads + while (1) { + int bytes_read = read(fifos[i], buff, 15); + if (bytes_read > 0) { + buff[bytes_read] = '\0'; + unsigned long val = strtoll(buff, NULL, 10); + if (val < max && val > min) { + cache[i] = val; + printf("%s: %lu\n", input_names[i], val); + } + else { + printf("%s: Bad value - input not received\n", input_names[i]); + } } - *pulse_width_us = gear; - break; - case 5: - // flap 1 - *pulse_width_us = 192000; - break; + pthread_yield(); } - return 0; + return NULL; } diff --git a/quad/src/virt_quad/hw_impl_unix_pwm_output.c b/quad/src/virt_quad/hw_impl_unix_pwm_output.c index b549cd4367af0a5ebfe8a50cd7af97e94daf16bb..e58d5cf5ae496a5fb6d6d4d76332d78097f98a9f 100644 --- a/quad/src/virt_quad/hw_impl_unix_pwm_output.c +++ b/quad/src/virt_quad/hw_impl_unix_pwm_output.c @@ -1,12 +1,65 @@ #include "hw_impl_unix.h" +#include <sys/types.h> +#include <sys/stat.h> +#include <fcntl.h> +#include <string.h> +#include <pthread.h> +#include <unistd.h> + +void * output_cache(); + +static char *output_pwms[4]; +static unsigned long cache[4]; +pthread_t worker; + +static int zero = 0; +static int one = 1; +static int two = 2; +static int three = 3; int unix_pwm_output_reset(struct PWMOutputDriver *self) { + output_pwms[0] = VIRT_QUAD_FIFOS_DIR "/pwm-output-motor1"; + output_pwms[1] = VIRT_QUAD_FIFOS_DIR "/pwm-output-motor2"; + output_pwms[2] = VIRT_QUAD_FIFOS_DIR "/pwm-output-motor3"; + output_pwms[3] = VIRT_QUAD_FIFOS_DIR "/pwm-output-motor4"; + + mkdir(VIRT_QUAD_FIFOS_DIR, 0777); + + // Start up worker thread whose job is to update the caches + pthread_create(&worker, 0, output_cache, &zero); + pthread_create(&worker, 0, output_cache, &one); + pthread_create(&worker, 0, output_cache, &two); + pthread_create(&worker, 0, output_cache, &three); + return 0; } int unix_pwm_output_write(struct PWMOutputDriver *self, unsigned int channel, unsigned long pulse_width_us) { - //printf("PWM OUTPUT: %d %d\n", channel, pulse_width_us); + if (cache[channel] != pulse_width_us) { + printf("%s: %ld\n", output_pwms[channel], pulse_width_us); + } + cache[channel] = pulse_width_us; return 0; } + +void * output_cache(void *arg) { + int *output_index = arg; + char buff[16]; + int i = *output_index; + + // Setup FIFO + unlink(output_pwms[i]); + mkfifo(output_pwms[i], 0666); + + // Block while waiting for someone to listen + while (1) { + int fifo = open(output_pwms[i], O_WRONLY); + sprintf(buff, "%ld\n", cache[i]); + write(fifo, buff, strlen(buff)); + close(fifo); + pthread_yield(); + } + return NULL; +} diff --git a/quad/src/virt_quad/hw_impl_unix_uart.c b/quad/src/virt_quad/hw_impl_unix_uart.c index c4f024ff282e6038f4ef63bd88a615fc14e9673f..e39fbedfc06f93a75a8e682cb44d81be98f790bf 100644 --- a/quad/src/virt_quad/hw_impl_unix_uart.c +++ b/quad/src/virt_quad/hw_impl_unix_uart.c @@ -1,70 +1,44 @@ #include "hw_impl_unix.h" -#include <sys/types.h> -#include <sys/socket.h> #include <stdio.h> -#include <sys/un.h> -#include <sys/ioctl.h> -#include <err.h> -#include <netinet/in.h> +#include <sys/stat.h> +#include <sys/types.h> +#include <fcntl.h> -#define DEFAULT_SOCKET "../../groundStation/virtquad.socket" -#define SOCKET_ENV "VIRT_QUAD_SOCKET" - -static int backendSocket; -static int client; +static char *fifo_full_name_rx; +static char *fifo_full_name_tx; +static int fifo_rx; int unix_uart_reset(struct UARTDriver *self) { - char * backend_socket_path = DEFAULT_SOCKET; - if (getenv(SOCKET_ENV)) { - backend_socket_path = getenv(SOCKET_ENV); - } - - /* Unlink if it exists */ - unlink(backend_socket_path); - printf("using socket '%s'\n", backend_socket_path); - - /* Create socket */ - backendSocket = socket(AF_UNIX, SOCK_STREAM | SOCK_NONBLOCK, 0); + fifo_full_name_rx = VIRT_QUAD_FIFOS_DIR "/uart-rx"; + fifo_full_name_tx = VIRT_QUAD_FIFOS_DIR "/uart-tx"; + char fifoname[64]; + mkdir(VIRT_QUAD_FIFOS_DIR, 0777); - /* Create sockaddr and bind */ - struct sockaddr_un sa; - sa.sun_family = AF_UNIX; - strncpy(sa.sun_path, backend_socket_path, strlen(backend_socket_path)); - sa.sun_path[strlen(backend_socket_path)+1] = '\0'; - if (bind(backendSocket, (struct sockaddr *) &sa, sizeof(sa))) { - err(-1, "bind"); - } + unlink(fifo_full_name_rx); + mkfifo(fifo_full_name_rx, 0666); + fifo_rx = open(fifo_full_name_rx, O_RDONLY | O_NONBLOCK); - /* Listen */ - if (listen(backendSocket, 1)) { - err(-1, "listen"); - } + unlink(fifo_full_name_tx); + mkfifo(fifo_full_name_tx, 0666); - while (1) { - client = accept(backendSocket, NULL, NULL); - if (client > 0) - break; - } - printf(" accpet() returned with %d\n", client); return 0; } int unix_uart_write(struct UARTDriver *self, unsigned char c) { - return send(client, &c, 1, MSG_DONTWAIT); - // return write(client, &c, 1); + int fifo = open(fifo_full_name_tx, O_WRONLY | O_NONBLOCK); + if (fifo >= 0) { + printf("%s: %x\n", "uart-tx", c); + write(fifo, &c, 1); + } + close(fifo); + return 0; } int unix_uart_read(struct UARTDriver *self, unsigned char *c) { - int bytes_available; - ioctl(client,FIONREAD,&bytes_available); - - if (bytes_available > 0) { - int bytes = recv(client, c, 1, 0); - printf("read in %d byte [%x]\n", bytes, *c); - return bytes; - } else { - return 0; - } - -} \ No newline at end of file + int err = read(fifo_rx, c, 1); + if (err > 0) { + printf("%s: %x\n", "uart-rx", *c); + } + return err <= 0; +} diff --git a/quad/src/virt_quad/main.c b/quad/src/virt_quad/main.c index a87b8013f5037d6a2db5badd74c7166f681e3e8c..f703f6ab77943a760ce7db7a1604ec672edb4e7b 100644 --- a/quad/src/virt_quad/main.c +++ b/quad/src/virt_quad/main.c @@ -1,6 +1,8 @@ #include <stdio.h> +#include <unistd.h> #include "hw_impl_unix.h" #include "quad_app.h" +#include <fcntl.h> int setup_hardware(hardware_t *hardware) { hardware->i2c = create_unix_i2c(); @@ -14,8 +16,21 @@ int setup_hardware(hardware_t *hardware) { return 0; } -int main() -{ +int main(int argc, char *argv[]) { + int fd, opt; + while ((opt = getopt(argc, argv, "q")) != -1) { + switch (opt) { + case 'q': + fd = open("/dev/null", O_WRONLY); + close(STDOUT_FILENO); + dup2(STDOUT_FILENO, fd); + break; + default: /* '?' */ + fprintf(stderr, "Usage: %s [-q]\n", argv[0]); + exit(EXIT_FAILURE); + } + } + quad_main(setup_hardware); return 0; } diff --git a/quad/xsdk_workspace/README.md b/quad/xsdk_workspace/README.md index 7e1cd0af615127935c4e2cec8b727b0ca1d5ef66..83a1f07277af48ac235145531a7032ffa58c1b82 100644 --- a/quad/xsdk_workspace/README.md +++ b/quad/xsdk_workspace/README.md @@ -1 +1,21 @@ -# Branch for hardware/software designs for Quadcopter +# XSDK Workspace + +This directory is reserved for XSDK projects. + +## Setup +XSDK, being based on Ecplise, is rather fragile, so do yourself a favor +and read this section so things get setup correctly. + +1. When you first open eclipse, select this directory, xsdk_workspace, as + your workspace (see what we did there?). + +2. When you get to your workbench, your project pane should be empty. To + add these projects, right-click on the project pane, and click on something + like "import projects". + + 1. Select "Import Existing Projects" (whereever that is) + 2. And then select the xsd_workspace as the folder where you want to import + projects. Add them all. + +3. If things are going swimmingly, then you should be able to build everyhing + and be off on your merry embedded endeavors. \ No newline at end of file diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/commands/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/commands/subdir.mk deleted file mode 100644 index f7ba0a3012665b52d4f33945aeb8058b155fa295..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/commands/subdir.mk +++ /dev/null @@ -1,24 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/commands/commands.c - -OBJS += \ -./ext/commands/commands.o - -C_DEPS += \ -./ext/commands/commands.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/commands/commands.o: /local/ucart/MicroCART_17-18/quad/src/commands/commands.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/computation_graph/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/computation_graph/subdir.mk deleted file mode 100644 index 6e59c9cee0577a04e7ea23b17ff244588d9e762d..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/computation_graph/subdir.mk +++ /dev/null @@ -1,24 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/computation_graph/computation_graph.c - -OBJS += \ -./ext/computation_graph/computation_graph.o - -C_DEPS += \ -./ext/computation_graph/computation_graph.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/computation_graph/computation_graph.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/computation_graph.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/graph_blocks/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/graph_blocks/subdir.mk deleted file mode 100644 index 2bb4dfce904ba88353ba7f556474171b44d79857..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/graph_blocks/subdir.mk +++ /dev/null @@ -1,114 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/graph_blocks.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_accumulator.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_add.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_bounds.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_constant.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_gain.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mixer.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mult.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pid.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pow.c - -OBJS += \ -./ext/graph_blocks/graph_blocks.o \ -./ext/graph_blocks/node_accumulator.o \ -./ext/graph_blocks/node_add.o \ -./ext/graph_blocks/node_bounds.o \ -./ext/graph_blocks/node_constant.o \ -./ext/graph_blocks/node_gain.o \ -./ext/graph_blocks/node_mixer.o \ -./ext/graph_blocks/node_mult.o \ -./ext/graph_blocks/node_pid.o \ -./ext/graph_blocks/node_pow.o - -C_DEPS += \ -./ext/graph_blocks/graph_blocks.d \ -./ext/graph_blocks/node_accumulator.d \ -./ext/graph_blocks/node_add.d \ -./ext/graph_blocks/node_bounds.d \ -./ext/graph_blocks/node_constant.d \ -./ext/graph_blocks/node_gain.d \ -./ext/graph_blocks/node_mixer.d \ -./ext/graph_blocks/node_mult.d \ -./ext/graph_blocks/node_pid.d \ -./ext/graph_blocks/node_pow.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/graph_blocks/graph_blocks.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/graph_blocks.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_accumulator.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_accumulator.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_add.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_add.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_bounds.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_bounds.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_constant.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_constant.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_gain.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_gain.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_mixer.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mixer.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_mult.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mult.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_pid.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pid.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_pow.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pow.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/quad_app/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/quad_app/subdir.mk deleted file mode 100644 index c3cc8861eb96ad0f808c5de24c00d27b8d74a657..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/quad_app/subdir.mk +++ /dev/null @@ -1,224 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/PID.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/actuator_command_processing.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/callbacks.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/communication.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/control_algorithm.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/controllers.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/conversion.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/iic_utils.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/initialize_components.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/log_data.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/mio7_led.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/new_log_data.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/packet_processing.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/quad_app.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/send_actuator_commands.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/sensor.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/sensor_processing.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/timer.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/update_gui.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/user_input.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/util.c - -OBJS += \ -./ext/quad_app/PID.o \ -./ext/quad_app/actuator_command_processing.o \ -./ext/quad_app/callbacks.o \ -./ext/quad_app/communication.o \ -./ext/quad_app/control_algorithm.o \ -./ext/quad_app/controllers.o \ -./ext/quad_app/conversion.o \ -./ext/quad_app/iic_utils.o \ -./ext/quad_app/initialize_components.o \ -./ext/quad_app/log_data.o \ -./ext/quad_app/mio7_led.o \ -./ext/quad_app/new_log_data.o \ -./ext/quad_app/packet_processing.o \ -./ext/quad_app/quad_app.o \ -./ext/quad_app/send_actuator_commands.o \ -./ext/quad_app/sensor.o \ -./ext/quad_app/sensor_processing.o \ -./ext/quad_app/timer.o \ -./ext/quad_app/update_gui.o \ -./ext/quad_app/user_input.o \ -./ext/quad_app/util.o - -C_DEPS += \ -./ext/quad_app/PID.d \ -./ext/quad_app/actuator_command_processing.d \ -./ext/quad_app/callbacks.d \ -./ext/quad_app/communication.d \ -./ext/quad_app/control_algorithm.d \ -./ext/quad_app/controllers.d \ -./ext/quad_app/conversion.d \ -./ext/quad_app/iic_utils.d \ -./ext/quad_app/initialize_components.d \ -./ext/quad_app/log_data.d \ -./ext/quad_app/mio7_led.d \ -./ext/quad_app/new_log_data.d \ -./ext/quad_app/packet_processing.d \ -./ext/quad_app/quad_app.d \ -./ext/quad_app/send_actuator_commands.d \ -./ext/quad_app/sensor.d \ -./ext/quad_app/sensor_processing.d \ -./ext/quad_app/timer.d \ -./ext/quad_app/update_gui.d \ -./ext/quad_app/user_input.d \ -./ext/quad_app/util.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/quad_app/PID.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/PID.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/actuator_command_processing.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/actuator_command_processing.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/callbacks.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/callbacks.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/communication.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/communication.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/control_algorithm.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/control_algorithm.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/controllers.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/controllers.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/conversion.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/conversion.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/iic_utils.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/iic_utils.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/initialize_components.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/initialize_components.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/log_data.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/log_data.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/mio7_led.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/mio7_led.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/new_log_data.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/new_log_data.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/packet_processing.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/packet_processing.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/quad_app.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/quad_app.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/send_actuator_commands.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/send_actuator_commands.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/sensor.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/sensor.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/sensor_processing.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/sensor_processing.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/timer.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/timer.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/update_gui.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/update_gui.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/user_input.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/user_input.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/util.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/util.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/queue/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/queue/subdir.mk deleted file mode 100644 index 8141db2ad3d477fa611ab8cb815bf102a059e2e3..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/ext/queue/subdir.mk +++ /dev/null @@ -1,24 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/queue/queue.c - -OBJS += \ -./ext/queue/queue.o - -C_DEPS += \ -./ext/queue/queue.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/queue/queue.o: /local/ucart/MicroCART_17-18/quad/src/queue/queue.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/makefile b/quad/xsdk_workspace/modular_quad_pid/Debug/makefile deleted file mode 100644 index 928243ba307f1025a6d169fd83c3abad121074c9..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/makefile +++ /dev/null @@ -1,63 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - --include ../makefile.init - -RM := rm -rf - -# All of the sources participating in the build are defined here --include sources.mk --include src/subdir.mk --include ext/queue/subdir.mk --include ext/quad_app/subdir.mk --include ext/graph_blocks/subdir.mk --include ext/computation_graph/subdir.mk --include ext/commands/subdir.mk --include subdir.mk --include objects.mk - -ifneq ($(MAKECMDGOALS),clean) -ifneq ($(strip $(C_DEPS)),) --include $(C_DEPS) -endif -ifneq ($(strip $(S_UPPER_DEPS)),) --include $(S_UPPER_DEPS) -endif -endif - --include ../makefile.defs - -# Add inputs and outputs from these tool invocations to the build variables -ELFSIZE += \ -modular_quad_pid.elf.size \ - - -# All Target -all: modular_quad_pid.elf secondary-outputs - -# Tool invocations -modular_quad_pid.elf: $(OBJS) ../src/lscript.ld $(USER_OBJS) - @echo 'Building target: $@' - @echo 'Invoking: ARM gcc linker' - arm-xilinx-eabi-gcc -Wl,-T -Wl,../src/lscript.ld -L../../system_bsp/ps7_cortexa9_0/lib -o "modular_quad_pid.elf" $(OBJS) $(USER_OBJS) $(LIBS) - @echo 'Finished building target: $@' - @echo ' ' - -modular_quad_pid.elf.size: modular_quad_pid.elf - @echo 'Invoking: ARM Print Size' - arm-xilinx-eabi-size modular_quad_pid.elf |tee "modular_quad_pid.elf.size" - @echo 'Finished building: $@' - @echo ' ' - -# Other Targets -clean: - -$(RM) $(OBJS)$(C_DEPS)$(EXECUTABLES)$(ELFSIZE)$(S_UPPER_DEPS) modular_quad_pid.elf - -@echo ' ' - -secondary-outputs: $(ELFSIZE) - -.PHONY: all clean dependents -.SECONDARY: - --include ../makefile.targets diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/objects.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/objects.mk deleted file mode 100644 index 24a8ef289ae38ceeb8f8ff8531c9bd851e7a09d0..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/objects.mk +++ /dev/null @@ -1,8 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -USER_OBJS := - -LIBS := -lm -Wl,--start-group,-lxil,-lgcc,-lc,--end-group - diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/sources.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/sources.mk deleted file mode 100644 index 9b76509427183193e779ddad577b92f06904d6a9..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/sources.mk +++ /dev/null @@ -1,25 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -O_SRCS := -C_SRCS := -LD_SRCS := -S_UPPER_SRCS := -S_SRCS := -OBJ_SRCS := -OBJS := -C_DEPS := -EXECUTABLES := -ELFSIZE := -S_UPPER_DEPS := - -# Every subdirectory with source files must be described here -SUBDIRS := \ -src \ -ext/queue \ -ext/quad_app \ -ext/graph_blocks \ -ext/computation_graph \ -ext/commands \ - diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/src/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/src/subdir.mk deleted file mode 100644 index 342be9a4df75c540826513b7781d20f55cec7e6e..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Debug/src/subdir.mk +++ /dev/null @@ -1,60 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -../src/hw_impl_zybo.c \ -../src/hw_impl_zybo_axi_timer.c \ -../src/hw_impl_zybo_global_timer.c \ -../src/hw_impl_zybo_i2c.c \ -../src/hw_impl_zybo_mio7_led.c \ -../src/hw_impl_zybo_pwm_input.c \ -../src/hw_impl_zybo_pwm_output.c \ -../src/hw_impl_zybo_system.c \ -../src/hw_impl_zybo_tests.c \ -../src/hw_impl_zybo_uart.c \ -../src/main.c \ -../src/platform.c - -LD_SRCS += \ -../src/lscript.ld - -OBJS += \ -./src/hw_impl_zybo.o \ -./src/hw_impl_zybo_axi_timer.o \ -./src/hw_impl_zybo_global_timer.o \ -./src/hw_impl_zybo_i2c.o \ -./src/hw_impl_zybo_mio7_led.o \ -./src/hw_impl_zybo_pwm_input.o \ -./src/hw_impl_zybo_pwm_output.o \ -./src/hw_impl_zybo_system.o \ -./src/hw_impl_zybo_tests.o \ -./src/hw_impl_zybo_uart.o \ -./src/main.o \ -./src/platform.o - -C_DEPS += \ -./src/hw_impl_zybo.d \ -./src/hw_impl_zybo_axi_timer.d \ -./src/hw_impl_zybo_global_timer.d \ -./src/hw_impl_zybo_i2c.d \ -./src/hw_impl_zybo_mio7_led.d \ -./src/hw_impl_zybo_pwm_input.d \ -./src/hw_impl_zybo_pwm_output.d \ -./src/hw_impl_zybo_system.d \ -./src/hw_impl_zybo_tests.d \ -./src/hw_impl_zybo_uart.d \ -./src/main.d \ -./src/platform.d - - -# Each subdirectory must supply rules for building sources it contributes -src/%.o: ../src/%.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -Wall -O0 -g3 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/ext/commands/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Release/ext/commands/subdir.mk deleted file mode 100644 index 8cdbd185e5ccf1c0be99a0d8fa96060a34e2b513..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/ext/commands/subdir.mk +++ /dev/null @@ -1,24 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/commands/commands.c - -OBJS += \ -./ext/commands/commands.o - -C_DEPS += \ -./ext/commands/commands.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/commands/commands.o: /local/ucart/MicroCART_17-18/quad/src/commands/commands.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/ext/computation_graph/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Release/ext/computation_graph/subdir.mk deleted file mode 100644 index b7232693ee94ab6bc1248c568cabec7ff1c42604..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/ext/computation_graph/subdir.mk +++ /dev/null @@ -1,24 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/computation_graph/computation_graph.c - -OBJS += \ -./ext/computation_graph/computation_graph.o - -C_DEPS += \ -./ext/computation_graph/computation_graph.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/computation_graph/computation_graph.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/computation_graph.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/ext/graph_blocks/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Release/ext/graph_blocks/subdir.mk deleted file mode 100644 index eb92d2e47df69bfc075f7f9f5e9eecc8d7a9f365..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/ext/graph_blocks/subdir.mk +++ /dev/null @@ -1,114 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/graph_blocks.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_accumulator.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_add.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_bounds.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_constant.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_gain.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mixer.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mult.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pid.c \ -/local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pow.c - -OBJS += \ -./ext/graph_blocks/graph_blocks.o \ -./ext/graph_blocks/node_accumulator.o \ -./ext/graph_blocks/node_add.o \ -./ext/graph_blocks/node_bounds.o \ -./ext/graph_blocks/node_constant.o \ -./ext/graph_blocks/node_gain.o \ -./ext/graph_blocks/node_mixer.o \ -./ext/graph_blocks/node_mult.o \ -./ext/graph_blocks/node_pid.o \ -./ext/graph_blocks/node_pow.o - -C_DEPS += \ -./ext/graph_blocks/graph_blocks.d \ -./ext/graph_blocks/node_accumulator.d \ -./ext/graph_blocks/node_add.d \ -./ext/graph_blocks/node_bounds.d \ -./ext/graph_blocks/node_constant.d \ -./ext/graph_blocks/node_gain.d \ -./ext/graph_blocks/node_mixer.d \ -./ext/graph_blocks/node_mult.d \ -./ext/graph_blocks/node_pid.d \ -./ext/graph_blocks/node_pow.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/graph_blocks/graph_blocks.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/graph_blocks.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_accumulator.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_accumulator.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_add.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_add.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_bounds.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_bounds.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_constant.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_constant.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_gain.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_gain.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_mixer.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mixer.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_mult.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_mult.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_pid.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pid.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/graph_blocks/node_pow.o: /local/ucart/MicroCART_17-18/quad/src/graph_blocks/node_pow.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/ext/quad_app/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Release/ext/quad_app/subdir.mk deleted file mode 100644 index d549e80dffda190f971af055c1a0540a81b5d411..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/ext/quad_app/subdir.mk +++ /dev/null @@ -1,224 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/PID.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/actuator_command_processing.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/callbacks.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/communication.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/control_algorithm.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/controllers.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/conversion.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/iic_utils.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/initialize_components.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/log_data.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/mio7_led.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/new_log_data.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/packet_processing.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/quad_app.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/send_actuator_commands.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/sensor.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/sensor_processing.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/timer.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/update_gui.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/user_input.c \ -/local/ucart/MicroCART_17-18/quad/src/quad_app/util.c - -OBJS += \ -./ext/quad_app/PID.o \ -./ext/quad_app/actuator_command_processing.o \ -./ext/quad_app/callbacks.o \ -./ext/quad_app/communication.o \ -./ext/quad_app/control_algorithm.o \ -./ext/quad_app/controllers.o \ -./ext/quad_app/conversion.o \ -./ext/quad_app/iic_utils.o \ -./ext/quad_app/initialize_components.o \ -./ext/quad_app/log_data.o \ -./ext/quad_app/mio7_led.o \ -./ext/quad_app/new_log_data.o \ -./ext/quad_app/packet_processing.o \ -./ext/quad_app/quad_app.o \ -./ext/quad_app/send_actuator_commands.o \ -./ext/quad_app/sensor.o \ -./ext/quad_app/sensor_processing.o \ -./ext/quad_app/timer.o \ -./ext/quad_app/update_gui.o \ -./ext/quad_app/user_input.o \ -./ext/quad_app/util.o - -C_DEPS += \ -./ext/quad_app/PID.d \ -./ext/quad_app/actuator_command_processing.d \ -./ext/quad_app/callbacks.d \ -./ext/quad_app/communication.d \ -./ext/quad_app/control_algorithm.d \ -./ext/quad_app/controllers.d \ -./ext/quad_app/conversion.d \ -./ext/quad_app/iic_utils.d \ -./ext/quad_app/initialize_components.d \ -./ext/quad_app/log_data.d \ -./ext/quad_app/mio7_led.d \ -./ext/quad_app/new_log_data.d \ -./ext/quad_app/packet_processing.d \ -./ext/quad_app/quad_app.d \ -./ext/quad_app/send_actuator_commands.d \ -./ext/quad_app/sensor.d \ -./ext/quad_app/sensor_processing.d \ -./ext/quad_app/timer.d \ -./ext/quad_app/update_gui.d \ -./ext/quad_app/user_input.d \ -./ext/quad_app/util.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/quad_app/PID.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/PID.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/actuator_command_processing.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/actuator_command_processing.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/callbacks.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/callbacks.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/communication.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/communication.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/control_algorithm.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/control_algorithm.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/controllers.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/controllers.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/conversion.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/conversion.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/iic_utils.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/iic_utils.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/initialize_components.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/initialize_components.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/log_data.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/log_data.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/mio7_led.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/mio7_led.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/new_log_data.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/new_log_data.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/packet_processing.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/packet_processing.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/quad_app.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/quad_app.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/send_actuator_commands.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/send_actuator_commands.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/sensor.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/sensor.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/sensor_processing.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/sensor_processing.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/timer.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/timer.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/update_gui.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/update_gui.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/user_input.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/user_input.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - -ext/quad_app/util.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/util.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/ext/queue/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Release/ext/queue/subdir.mk deleted file mode 100644 index a595cf53e1bd98da9251d9166acf07f43e6f6651..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/ext/queue/subdir.mk +++ /dev/null @@ -1,24 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -/local/ucart/MicroCART_17-18/quad/src/queue/queue.c - -OBJS += \ -./ext/queue/queue.o - -C_DEPS += \ -./ext/queue/queue.d - - -# Each subdirectory must supply rules for building sources it contributes -ext/queue/queue.o: /local/ucart/MicroCART_17-18/quad/src/queue/queue.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/makefile b/quad/xsdk_workspace/modular_quad_pid/Release/makefile deleted file mode 100644 index 928243ba307f1025a6d169fd83c3abad121074c9..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/makefile +++ /dev/null @@ -1,63 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - --include ../makefile.init - -RM := rm -rf - -# All of the sources participating in the build are defined here --include sources.mk --include src/subdir.mk --include ext/queue/subdir.mk --include ext/quad_app/subdir.mk --include ext/graph_blocks/subdir.mk --include ext/computation_graph/subdir.mk --include ext/commands/subdir.mk --include subdir.mk --include objects.mk - -ifneq ($(MAKECMDGOALS),clean) -ifneq ($(strip $(C_DEPS)),) --include $(C_DEPS) -endif -ifneq ($(strip $(S_UPPER_DEPS)),) --include $(S_UPPER_DEPS) -endif -endif - --include ../makefile.defs - -# Add inputs and outputs from these tool invocations to the build variables -ELFSIZE += \ -modular_quad_pid.elf.size \ - - -# All Target -all: modular_quad_pid.elf secondary-outputs - -# Tool invocations -modular_quad_pid.elf: $(OBJS) ../src/lscript.ld $(USER_OBJS) - @echo 'Building target: $@' - @echo 'Invoking: ARM gcc linker' - arm-xilinx-eabi-gcc -Wl,-T -Wl,../src/lscript.ld -L../../system_bsp/ps7_cortexa9_0/lib -o "modular_quad_pid.elf" $(OBJS) $(USER_OBJS) $(LIBS) - @echo 'Finished building target: $@' - @echo ' ' - -modular_quad_pid.elf.size: modular_quad_pid.elf - @echo 'Invoking: ARM Print Size' - arm-xilinx-eabi-size modular_quad_pid.elf |tee "modular_quad_pid.elf.size" - @echo 'Finished building: $@' - @echo ' ' - -# Other Targets -clean: - -$(RM) $(OBJS)$(C_DEPS)$(EXECUTABLES)$(ELFSIZE)$(S_UPPER_DEPS) modular_quad_pid.elf - -@echo ' ' - -secondary-outputs: $(ELFSIZE) - -.PHONY: all clean dependents -.SECONDARY: - --include ../makefile.targets diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/objects.mk b/quad/xsdk_workspace/modular_quad_pid/Release/objects.mk deleted file mode 100644 index 24a8ef289ae38ceeb8f8ff8531c9bd851e7a09d0..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/objects.mk +++ /dev/null @@ -1,8 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -USER_OBJS := - -LIBS := -lm -Wl,--start-group,-lxil,-lgcc,-lc,--end-group - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/sources.mk b/quad/xsdk_workspace/modular_quad_pid/Release/sources.mk deleted file mode 100644 index 9b76509427183193e779ddad577b92f06904d6a9..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/sources.mk +++ /dev/null @@ -1,25 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -O_SRCS := -C_SRCS := -LD_SRCS := -S_UPPER_SRCS := -S_SRCS := -OBJ_SRCS := -OBJS := -C_DEPS := -EXECUTABLES := -ELFSIZE := -S_UPPER_DEPS := - -# Every subdirectory with source files must be described here -SUBDIRS := \ -src \ -ext/queue \ -ext/quad_app \ -ext/graph_blocks \ -ext/computation_graph \ -ext/commands \ - diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/src/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Release/src/subdir.mk deleted file mode 100644 index d73a8e4edf8f1be1d1cb7bbc2866698e8091f6d0..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/Release/src/subdir.mk +++ /dev/null @@ -1,60 +0,0 @@ -################################################################################ -# Automatically-generated file. Do not edit! -################################################################################ - -# Add inputs and outputs from these tool invocations to the build variables -C_SRCS += \ -../src/hw_impl_zybo.c \ -../src/hw_impl_zybo_axi_timer.c \ -../src/hw_impl_zybo_global_timer.c \ -../src/hw_impl_zybo_i2c.c \ -../src/hw_impl_zybo_mio7_led.c \ -../src/hw_impl_zybo_pwm_input.c \ -../src/hw_impl_zybo_pwm_output.c \ -../src/hw_impl_zybo_system.c \ -../src/hw_impl_zybo_tests.c \ -../src/hw_impl_zybo_uart.c \ -../src/main.c \ -../src/platform.c - -LD_SRCS += \ -../src/lscript.ld - -OBJS += \ -./src/hw_impl_zybo.o \ -./src/hw_impl_zybo_axi_timer.o \ -./src/hw_impl_zybo_global_timer.o \ -./src/hw_impl_zybo_i2c.o \ -./src/hw_impl_zybo_mio7_led.o \ -./src/hw_impl_zybo_pwm_input.o \ -./src/hw_impl_zybo_pwm_output.o \ -./src/hw_impl_zybo_system.o \ -./src/hw_impl_zybo_tests.o \ -./src/hw_impl_zybo_uart.o \ -./src/main.o \ -./src/platform.o - -C_DEPS += \ -./src/hw_impl_zybo.d \ -./src/hw_impl_zybo_axi_timer.d \ -./src/hw_impl_zybo_global_timer.d \ -./src/hw_impl_zybo_i2c.d \ -./src/hw_impl_zybo_mio7_led.d \ -./src/hw_impl_zybo_pwm_input.d \ -./src/hw_impl_zybo_pwm_output.d \ -./src/hw_impl_zybo_system.d \ -./src/hw_impl_zybo_tests.d \ -./src/hw_impl_zybo_uart.d \ -./src/main.d \ -./src/platform.d - - -# Each subdirectory must supply rules for building sources it contributes -src/%.o: ../src/%.c - @echo 'Building file: $<' - @echo 'Invoking: ARM gcc compiler' - arm-xilinx-eabi-gcc -DNDEBUG=1 -Wall -O2 -I../../system_bsp/ps7_cortexa9_0/include -I"/local/ucart/MicroCART_17-18/quad/src/computation_graph" -I"/local/ucart/MicroCART_17-18/quad/src/quad_app" -I"/local/ucart/MicroCART_17-18/quad/src/queue" -I"/local/ucart/MicroCART_17-18/quad/src/commands" -I"/local/ucart/MicroCART_17-18/quad/src/graph_blocks" -c -fmessage-length=0 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" - @echo 'Finished building: $<' - @echo ' ' - - diff --git a/quad/xsdk_workspace/modular_quad_pid/src/queue.c b/quad/xsdk_workspace/modular_quad_pid/src/queue.c deleted file mode 120000 index 6b67b81f59670abf26db748c7d699d766c909ae8..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/src/queue.c +++ /dev/null @@ -1 +0,0 @@ -../../../../lib/queue/queue.c \ No newline at end of file diff --git a/quad/xsdk_workspace/modular_quad_pid/src/queue.h b/quad/xsdk_workspace/modular_quad_pid/src/queue.h deleted file mode 120000 index b9524b35495f9ec9badf16668b107d0f72d38556..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/modular_quad_pid/src/queue.h +++ /dev/null @@ -1 +0,0 @@ -../../../../lib/queue/queue.h \ No newline at end of file diff --git a/quad/xsdk_workspace/modular_quad_pid/.cproject b/quad/xsdk_workspace/real_quad/.cproject similarity index 97% rename from quad/xsdk_workspace/modular_quad_pid/.cproject rename to quad/xsdk_workspace/real_quad/.cproject index f17eeafddf9cc8821dcdd8ee953460b8a2f47b55..562e459ecf4b9d080872b43dd40b5a813409d745 100644 --- a/quad/xsdk_workspace/modular_quad_pid/.cproject +++ b/quad/xsdk_workspace/real_quad/.cproject @@ -27,15 +27,15 @@ <tool id="xilinx.gnu.arm.c.toolchain.compiler.debug.177835003" name="ARM gcc compiler" superClass="xilinx.gnu.arm.c.toolchain.compiler.debug"> <option defaultValue="gnu.c.optimization.level.none" id="xilinx.gnu.compiler.option.optimization.level.1900496019" name="Optimization Level" superClass="xilinx.gnu.compiler.option.optimization.level" value="gnu.c.optimization.level.none" valueType="enumerated"/> <option id="xilinx.gnu.compiler.option.debugging.level.1207856754" name="Debug Level" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.max" valueType="enumerated"/> - <option id="xilinx.gnu.compiler.inferred.swplatform.includes.2123463819" name="Software Platform Include Path" superClass="xilinx.gnu.compiler.inferred.swplatform.includes" valueType="includePath"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.2123463819" name="Software Platform Include Path" superClass="xilinx.gnu.compiler.inferred.swplatform.includes"/> <option id="xilinx.gnu.compiler.symbols.defined.1696008720" name="Defined symbols (-D)" superClass="xilinx.gnu.compiler.symbols.defined"/> <option id="xilinx.gnu.compiler.dircategory.includes.1211006365" name="Include Paths" superClass="xilinx.gnu.compiler.dircategory.includes" valueType="includePath"> <listOptionValue builtIn="false" value="../../system_bsp/ps7_cortexa9_0/include"/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/computation_graph}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/quad_app}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/queue}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/commands}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/graph_blocks}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/commands}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/computation_graph}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/graph_blocks}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/quad_app}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/queue}""/> </option> <inputType id="xilinx.gnu.arm.c.compiler.input.909725989" name="C source files" superClass="xilinx.gnu.arm.c.compiler.input"/> </tool> @@ -114,11 +114,11 @@ </option> <option id="xilinx.gnu.compiler.dircategory.includes.1873624761" name="Include Paths" superClass="xilinx.gnu.compiler.dircategory.includes" valueType="includePath"> <listOptionValue builtIn="false" value="../../system_bsp/ps7_cortexa9_0/include"/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/computation_graph}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/quad_app}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/queue}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/commands}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/modular_quad_pid/ext/graph_blocks}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/computation_graph}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/quad_app}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/queue}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/commands}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/real_quad/ext/graph_blocks}""/> </option> <inputType id="xilinx.gnu.arm.c.compiler.input.846429887" name="C source files" superClass="xilinx.gnu.arm.c.compiler.input"/> </tool> diff --git a/quad/xsdk_workspace/modular_quad_pid/.gitignore b/quad/xsdk_workspace/real_quad/.gitignore similarity index 68% rename from quad/xsdk_workspace/modular_quad_pid/.gitignore rename to quad/xsdk_workspace/real_quad/.gitignore index 0172c96483ac5bc2da8b0612023c28d29f1c4525..8274dfc9f03b3d46129a53606ca8ddd09c715e2f 100644 --- a/quad/xsdk_workspace/modular_quad_pid/.gitignore +++ b/quad/xsdk_workspace/real_quad/.gitignore @@ -3,3 +3,5 @@ *.elf *.size bootimage/ +Debug/ +Release/ \ No newline at end of file diff --git a/quad/xsdk_workspace/modular_quad_pid/.project b/quad/xsdk_workspace/real_quad/.project similarity index 98% rename from quad/xsdk_workspace/modular_quad_pid/.project rename to quad/xsdk_workspace/real_quad/.project index 734130fb55d695ee28de0b41cc6b8f0f4bccd05e..0cccbe569870d07d3ae983f76ba11fe60bce4b35 100644 --- a/quad/xsdk_workspace/modular_quad_pid/.project +++ b/quad/xsdk_workspace/real_quad/.project @@ -1,6 +1,6 @@ <?xml version="1.0" encoding="UTF-8"?> <projectDescription> - <name>modular_quad_pid</name> + <name>real_quad</name> <comment></comment> <projects> <project>system_bsp</project> @@ -53,7 +53,7 @@ </linkedResources> <filteredResources> <filter> - <id>1489164394345</id> + <id>1490997289335</id> <name></name> <type>10</type> <matcher> diff --git a/quad/xsdk_workspace/real_quad/.settings/org.eclipse.cdt.codan.core.prefs b/quad/xsdk_workspace/real_quad/.settings/org.eclipse.cdt.codan.core.prefs new file mode 100644 index 0000000000000000000000000000000000000000..8e0550446a2bb045d01a9f8b73d47305f777665c --- /dev/null +++ b/quad/xsdk_workspace/real_quad/.settings/org.eclipse.cdt.codan.core.prefs @@ -0,0 +1,34 @@ +eclipse.preferences.version=1 +org.eclipse.cdt.codan.checkers.errnoreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false} +org.eclipse.cdt.codan.checkers.errreturnvalue.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.checkers.noreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false} +org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},no_break_comment\=>"no break",last_case_param\=>false,empty_case_param\=>false} +org.eclipse.cdt.codan.internal.checkers.CatchByReference.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},unknown\=>false,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},skip\=>true} +org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.InvalidArguments.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},pattern\=>"^[a-z]",macro\=>true,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.OverloadProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},paramNot\=>false} +org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},else\=>false,afterelse\=>false} +org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true} +org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true} +org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>("@(\#)","$Id")} +org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} diff --git a/quad/xsdk_workspace/modular_quad_pid/ext/__CAUTION__.md b/quad/xsdk_workspace/real_quad/ext/__CAUTION__.md similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/ext/__CAUTION__.md rename to quad/xsdk_workspace/real_quad/ext/__CAUTION__.md diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.h b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo.h similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.h rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo.h diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_axi_timer.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_axi_timer.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_axi_timer.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_axi_timer.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_global_timer.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_global_timer.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_global_timer.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_global_timer.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_i2c.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_i2c.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_i2c.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_i2c.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_mio7_led.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_mio7_led.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_mio7_led.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_mio7_led.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_input.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_pwm_input.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_input.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_pwm_input.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_output.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_pwm_output.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_output.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_pwm_output.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_system.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_system.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_system.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_system.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_tests.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_tests.c similarity index 99% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_tests.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_tests.c index 8fa79cbb283532fed1a65e8c37a80d1c4c489e28..2f5e5ab43e06ae7091ba3b0b1eba5d66ffbf0e7c 100644 --- a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_tests.c +++ b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_tests.c @@ -230,7 +230,7 @@ int test_zybo_global_timer() { * 2) Set the RUN_TESTS macro in main.c * 3) Uncomment only this test in main.c * 4) Run main.c - * 5) Execute quad/scripts/test_zybo_uart.py + * 5) Execute quad/scripts/tests/test_zybo_uart.py * - Observe test results on terminal * - You might be able to see LED MIO7 blink when it receives bytes */ diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_uart.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_uart.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_uart.c rename to quad/xsdk_workspace/real_quad/src/hw_impl_zybo_uart.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/lscript.ld b/quad/xsdk_workspace/real_quad/src/lscript.ld similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/lscript.ld rename to quad/xsdk_workspace/real_quad/src/lscript.ld diff --git a/quad/xsdk_workspace/modular_quad_pid/src/main.c b/quad/xsdk_workspace/real_quad/src/main.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/main.c rename to quad/xsdk_workspace/real_quad/src/main.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/platform.c b/quad/xsdk_workspace/real_quad/src/platform.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/platform.c rename to quad/xsdk_workspace/real_quad/src/platform.c diff --git a/quad/xsdk_workspace/modular_quad_pid/src/platform.h b/quad/xsdk_workspace/real_quad/src/platform.h similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/platform.h rename to quad/xsdk_workspace/real_quad/src/platform.h diff --git a/quad/xsdk_workspace/modular_quad_pid/src/platform_config.h b/quad/xsdk_workspace/real_quad/src/platform_config.h similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/src/platform_config.h rename to quad/xsdk_workspace/real_quad/src/platform_config.h diff --git a/quad/xsdk_workspace/modular_quad_pid/test/.gitignore b/quad/xsdk_workspace/real_quad/test/.gitignore similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/test/.gitignore rename to quad/xsdk_workspace/real_quad/test/.gitignore diff --git a/quad/xsdk_workspace/modular_quad_pid/test/Makefile b/quad/xsdk_workspace/real_quad/test/Makefile similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/test/Makefile rename to quad/xsdk_workspace/real_quad/test/Makefile diff --git a/quad/xsdk_workspace/modular_quad_pid/test/test_uart_buff.c b/quad/xsdk_workspace/real_quad/test/test_uart_buff.c similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/test/test_uart_buff.c rename to quad/xsdk_workspace/real_quad/test/test_uart_buff.c diff --git a/quad/xsdk_workspace/modular_quad_pid/test/xil_types.h b/quad/xsdk_workspace/real_quad/test/xil_types.h similarity index 100% rename from quad/xsdk_workspace/modular_quad_pid/test/xil_types.h rename to quad/xsdk_workspace/real_quad/test/xil_types.h