diff --git a/ci-build.sh b/ci-build.sh index af6f06ee2b0ac51bbf2ca42d1819684979dd267e..f2ee59eb3b1ecf1ff64936b8e32e215800177266 100644 --- a/ci-build.sh +++ b/ci-build.sh @@ -1,7 +1,6 @@ #!/bin/bash -PROJECT_ROOT=$(pwd) -export PROJECT_ROOT +set -e -# Quad -bash quad/ci-build.sh || exit 1 +# Quad Libraries and Boot image +cd quad && make boot diff --git a/ci-test.sh b/ci-test.sh index 5542a1b99fad91c60197f1aa8189a780316b94ff..4504f9a6d9d422964da0fc469bcba52befdb65e2 100644 --- a/ci-test.sh +++ b/ci-test.sh @@ -1,7 +1,6 @@ #!/bin/bash -PROJECT_ROOT=$(pwd) -export PROJECT_ROOT +set -e # Quad -bash quad/ci-test.sh || exit 1 +cd quad && make && make test diff --git a/groundStation/src/backend/commands.c b/common/commands.c similarity index 71% rename from groundStation/src/backend/commands.c rename to common/commands.c index 4bba287358dacb4f9ad545073d983c6b89600e9d..09f18bcaeefb6c8ecbcffd4342c0ce7b68c59d14 100644 --- a/groundStation/src/backend/commands.c +++ b/common/commands.c @@ -55,12 +55,24 @@ command_cb cb_update __attribute__((weak, alias("cb_default"))); command_cb cb_beginupdate __attribute__((weak, alias("cb_default"))); command_cb cb_log __attribute__((weak, alias("cb_default"))); command_cb cb_response __attribute__((weak, alias("cb_default"))); +command_cb cb_logend __attribute__((weak, alias("cb_default"))); /* Callbacks for configuration */ command_cb cb_setparam __attribute__((weak, alias("cb_default"))); command_cb cb_getparam __attribute__((weak, alias("cb_default"))); command_cb cb_respparam __attribute__((weak, alias("cb_default"))); +command_cb cb_setsource __attribute__((weak, alias("cb_default"))); +command_cb cb_getsource __attribute__((weak, alias("cb_default"))); +command_cb cb_respsource __attribute__((weak, alias("cb_default"))); + +command_cb cb_getoutput __attribute__((weak, alias("cb_default"))); +command_cb cb_respoutput __attribute__((weak, alias("cb_default"))); + +command_cb cb_getnodes __attribute__((weak, alias("cb_default"))); +command_cb cb_respnodes __attribute__((weak, alias("cb_default"))); + + /* * Command structure. * This array is used to keep track of the callback functions @@ -163,15 +175,86 @@ struct MessageType MessageTypes[MAX_TYPE_ID] = floatType, // Function pointer &cb_respparam + }, + // SETSOURCE + { + // Command text + "setsource", + // Type of the command data + floatType, + // Function pointer + &cb_setsource + }, + // GETSOURCE + { + // Command text + "getsource", + // Type of the command data + floatType, + // Function pointer + &cb_getsource + }, + // RESPSOURCE + { + // Command text + "respsource", + // Type of the command data + floatType, + // Function pointer + &cb_respsource + }, + // GETOUTPUT + { + // Command text + "getoutput", + // Type of the command data + floatType, + // Function pointer + &cb_respoutput + }, + // RESPOUTPUT + { + // Command text + "respoutput", + // Type of the command data + floatType, + // Function pointer + &cb_respoutput + }, + // GETNODES + { + // Command text + "getnodes", + // Type of the command data + floatType, + // Function pointer + &cb_getnodes + }, + // RESPNODES + { + // Command text + "respnodes", + // Type of the command data + floatType, + // Function pointer + &cb_respnodes + }, + // LOG_END + { + // Command text + "logend", + // Type of the command data + stringType, + // Function pointer + &cb_logend } - }; int findCommand(char * str) { int i; for (i = 0; i < MAX_TYPE_ID; i++) { - if (strcmp(str, MessageTypes[i].cmdText) == 0) { + if (strncmp(str, MessageTypes[i].cmdText, strlen(str)) == 0) { return i; } } diff --git a/groundStation/src/backend/commands.h b/common/commands.h similarity index 58% rename from groundStation/src/backend/commands.h rename to common/commands.h index 73ec98f953a12e910ce7fbdec572dcb95c4fb6a6..86fa2c897cf54f090af5e333ae7e755a64f30505 100644 --- a/groundStation/src/backend/commands.h +++ b/common/commands.h @@ -29,7 +29,8 @@ enum DataType * Message type IDs used to know what kind of message we are dealing with * Enumeration used to index the MessageTypes array in commands.c * - * DO NOT change this enum or you will break backwards compatibility. + * DO NOT change items in the middle of this enum or you will break backwards compatibility. + * - Add new message types in the slot between MAX_TYPE_ID and the one before it * DO NOT change this enum without also updating the "MessageTypes" array * in commands.c to match. */ @@ -44,38 +45,16 @@ enum MessageTypeID{ SETPARAM_ID, // 07 - Setting controller parameters. Example: PID constants GETPARAM_ID, // 08 - Getting controller parameters. Example: PID constants RESPPARAM_ID, // 09 - Responding with controller parameters. Example: PID constants - MAX_TYPE_ID // 10 - Just used to keep track of the size + SETSOURCE_ID, // 10 - Setting controller source Block & id + GETSOURCE_ID, // 11 - Getting controller source Block & id + RESPSOURCE_ID, // 12 - Responding with controller source Block & id + GETOUTPUT_ID, // 13 - Getting controller block output + RESPOUTPUT_ID, // 14 - Responding with controller block output + GETNODES_ID, // 15 - Getting nodes from current comp_graph + RESPNODES_ID, // 16 - Responding with nodes from current comp_graph + LOG_END_ID, // 17 - Responding with controller parameters. Example: PID constants + MAX_TYPE_ID // 18 - Just used to keep track of the size. Must remain at the end }; - -/* - * Controller ID used to know which controller the message is referencing - */ -enum ControllerID{ - ROLL_ID, // 00 - Roll PID - PITCH_ID, // 01 - Pitch PID - YAW_ID, // 02 - Yaw PID - ROLL_RATE_ID, // 03 - Roll rate PID - PITCH_RATE_ID, // 04 - Pitch rate PID - YAW_RATE_ID, // 05 - Yaw rate PID - LOCAL_X_ID, // 06 - Local X PID // lat - LOCAL_Y_ID, // 07 - Local Y PID //long - ALT_ID, // 08 - Altitude PID - X_SETPOINT_ID, // 09 - X Setpoint //lat - Y_SETPOINT_ID, // 10 - Y Setpoint //long - ALT_SETPOINT_ID, // 11 - Z Setpoint - MAX_CONTROLLER_ID // 12 - Just used to keep track of the size -}; - -/* - * Enumeration of controller parameters - */ -enum ControlParamID{ - KP_ID, // 00 - P constant - KI_ID, // 01 - I constant - KD_ID, // 02 - D constant - MAX_CONTROL_PARAM_ID, // 03 - Just used to keep track of the size -}; - /* * Message type struct used to keep track of the callback function * pointers located in commands.c diff --git a/groundStation/src/backend/common/common.txt b/common/common.txt similarity index 50% rename from groundStation/src/backend/common/common.txt rename to common/common.txt index cfc7835508714bcbc03e48f3af52c4b69e172a2a..3a20094073732be5f5bed0035644f2193a85cdbc 100644 --- a/groundStation/src/backend/common/common.txt +++ b/common/common.txt @@ -1,7 +1,3 @@ The common files are: - - packet.h - - packet.c - setcontrol.h - setcontrol.c - - bitwise.h - - controller.h diff --git a/groundStation/src/backend/common/examples.c b/common/examples_c similarity index 100% rename from groundStation/src/backend/common/examples.c rename to common/examples_c diff --git a/controls/DataAnalysisTool/Tool/simplePlots.m b/controls/DataAnalysisTool/Tool/simplePlots.m new file mode 100644 index 0000000000000000000000000000000000000000..edd91bf4aa05002531109897c7c0f6ca162ed387 --- /dev/null +++ b/controls/DataAnalysisTool/Tool/simplePlots.m @@ -0,0 +1,70 @@ +%% +plot(Time, Cam_Meas_Roll*(180/pi)); hold on; +plot(Time, Quad_Meas_Roll*(180/pi)); + +%% +plot(Time, pitch_velocity*(180/pi)); hold on; +plot(Time, roll_velocity*(180/pi)); +plot(Time, yaw_velocity*(180/pi)); + +%% +figure; +plot(time, VRPNPitchConstant*(180/pi)); hold on; +plot(time, PitchConstant*(180/pi)); +legend('Camera Pitch', 'Quad Pitch'); +xlabel('seconds'); ylabel('degrees'); + +%% +figure; +plot(time, (VRPNRollConstant + pi)*(180/pi)); hold on; +plot(time, RollConstant*(180/pi)); +legend('Camera Roll', 'Quad Roll'); +xlabel('seconds'); ylabel('degrees'); + +%% +%plot(Time, X_setpoint); hold on; +markerSize = 3; +ax1 = subplot(2,1,1); +plot(time, (XSetpointConstant - VRPNXConstant), '-o', 'MarkerSize', markerSize); hold on; +plot(time, -XposPIDCorrection * (180/pi), '-o', 'MarkerSize', markerSize); hold off; +legend('X Error', 'X PID output'); + + +ax2 = subplot(2,1,2); +plot(time, (180/pi)*PitchConstant, '-o', 'MarkerSize', markerSize); hold on; +plot(time, (180/pi)*PitchPIDCorrection, '-o', 'MarkerSize', markerSize); +legend('Pitch Error', 'Pitch PID output'); + +linkaxes([ax1, ax2], 'x'); +%% +ax2 = subplot(2,2,1); +plot(time, XSetpointConstant - VRPNXConstant); +title('X error'); + +ax1 = subplot(2,2,2); +plot(time, XposPIDCorrection); +title('x output'); + +ax3 = subplot(2,2,3); +plot(time, PitchPIDCorrection); hold on; +plot(time, VRPNPitchConstant .* 10); +title('pitch output'); +legend('output', 'Pitch'); + +ax4 = subplot(2,2,4); +plot(time, PitchRatePIDCorrection); hold on; +plot(time, gyro_y .* 1044.26); +legend('output', 'Pitch rate'); +title('pitch rate output'); + +linkaxes([ax1, ax2, ax3, ax4], 'x'); +%% +plot(time, 1044.26 .* (PitchPIDCorrection - gyro_y));hold on; +%plot(time, PitchRatePIDCorrection); +%% +ax2 = subplot(2, 1, 1); +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 diff --git a/controls/MATLAB/IMU/IMU_dataAnalysis_allFilters/analyzeIMU_data.m b/controls/MATLAB/IMU/IMU_dataAnalysis_allFilters/analyzeIMU_data.m new file mode 100644 index 0000000000000000000000000000000000000000..819117c5489e9c503c171d031f8edeacb780b545 --- /dev/null +++ b/controls/MATLAB/IMU/IMU_dataAnalysis_allFilters/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/MATLAB/IMU/IMU_dataAnalysis_allFilters/analyzeIMU_data_allFilters.m b/controls/MATLAB/IMU/IMU_dataAnalysis_allFilters/analyzeIMU_data_allFilters.m new file mode 100644 index 0000000000000000000000000000000000000000..8570c8a7f4061607265762fbe65ecb264f740a09 --- /dev/null +++ b/controls/MATLAB/IMU/IMU_dataAnalysis_allFilters/analyzeIMU_data_allFilters.m @@ -0,0 +1,11 @@ +%Run through IMU data for all filters (levels 0 to 6): + +% for i = 0:1:6 +% +% fileName = [ 'level' , num2str(i) , '.csv' ]; +% analyzeIMU_data( fileName ); +% +% end + +fileName = 'level5.csv'; +analyzeIMU_data( fileName ); \ No newline at end of file diff --git a/controls/dataCollection/IMU_standstill/CompiledData.xlsx b/controls/dataCollection/IMU_standstill/CompiledData.xlsx new file mode 100644 index 0000000000000000000000000000000000000000..d978efb34861bd7e21907cb08e3ef73cd5fa595e Binary files /dev/null and b/controls/dataCollection/IMU_standstill/CompiledData.xlsx differ diff --git a/controls/model/c_controller.c b/controls/model/c_controller.c new file mode 100644 index 0000000000000000000000000000000000000000..6bcee0997d9c72199d6983b738bac881478fdbe6 --- /dev/null +++ b/controls/model/c_controller.c @@ -0,0 +1,72 @@ +#include "c_controller.h" +#include "quad_files/control_algorithm.c" +#include "quad_files/computation_graph.c" +double c_controller(int vrpn_id, double vrpn_ts, double set_x, double set_y, double set_z, double set_yaw, + double cur_x, double cur_y, double cur_z, + double cur_phi, double cur_theta, double cur_psi, + double cur_phi_d, double cur_theta_d, double cur_psi_d, + double *z_out, double *y_out, double *x_out, double *yaw_out, + double* pid_y_out, double* pid_roll_out) { + + static log_t log_struct; + static user_input_t user_input_struct; + static sensor_t sensor_struct; + static setpoint_t setpoint_struct; + static parameter_t ps; + static user_defined_t user_defined_struct; + static actuator_command_t actuator_struct; + static modular_structs_t structs; + + static int last_vrpn_id = -1; + static int initialized = 0; + if (!initialized) { + control_algorithm_init(&ps); + sensor_struct.currentQuadPosition.packetId = vrpn_id; + initialized = 1; + } + + // Check VRPN update + if (vrpn_id != last_vrpn_id) { + user_input_struct.locationFresh = 1; + int vrpn_ts_packets = (vrpn_ts / 0.01) + 0.5; // + 0.5 to round + sensor_struct.currentQuadPosition.packetId += vrpn_ts_packets; + // VRPN values + sensor_struct.currentQuadPosition.x_pos = cur_x; + sensor_struct.currentQuadPosition.y_pos = cur_y; + sensor_struct.currentQuadPosition.alt_pos = cur_z; + sensor_struct.currentQuadPosition.pitch = cur_theta; + sensor_struct.currentQuadPosition.roll = cur_phi; + sensor_struct.currentQuadPosition.yaw = cur_psi; + last_vrpn_id = vrpn_id; + } + + // Setpoints + /* + setpoint_struct.desiredQuadPosition.x_pos = set_x; + setpoint_struct.desiredQuadPosition.y_pos = set_y; + setpoint_struct.desiredQuadPosition.alt_pos = set_z; + setpoint_struct.desiredQuadPosition.yaw = set_yaw; + */ + int i; + + // Sensors + sensor_struct.pitch_angle_filtered = cur_theta; + sensor_struct.roll_angle_filtered = cur_phi; + sensor_struct.theta_dot = cur_theta_d; + sensor_struct.phi_dot = cur_phi_d; + sensor_struct.psi_dot = cur_psi_d; + + control_algorithm(&log_struct, &user_input_struct, &sensor_struct, &setpoint_struct, &ps, &user_defined_struct, &actuator_struct, NULL); + + *z_out = graph_get_output(ps.graph, ps.alt_pid, PID_CORRECTION); + *y_out = graph_get_output(ps.graph, ps.roll_r_pid, PID_CORRECTION); + *x_out = graph_get_output(ps.graph, ps.pitch_r_pid, PID_CORRECTION); + *yaw_out = graph_get_output(ps.graph, ps.yaw_r_pid, PID_CORRECTION); + + *pid_y_out = graph_get_output(ps.graph, ps.y_pos_pid, PID_CORRECTION); + *pid_roll_out = graph_get_output(ps.graph, ps.roll_pid, PID_CORRECTION); + return 0; +} + +int read_flap(int flap) { return AUTO_FLIGHT_MODE; } +float get_last_loop_time() { return 0.005; } diff --git a/controls/model/c_controller.h b/controls/model/c_controller.h new file mode 100644 index 0000000000000000000000000000000000000000..e53b1a508409d70211a99fe6ba6de76e092ae7a5 --- /dev/null +++ b/controls/model/c_controller.h @@ -0,0 +1,18 @@ +#ifndef C_CONTROLLER_H +#define C_CONTROLLER_H +#include "quad_files/computation_graph.h" +#include "quad_files/graph_blocks/node_pid.h" +#include "quad_files/graph_blocks/node_bounds.h" +#include "quad_files/graph_blocks/node_constant.h" +#include "quad_files/graph_blocks/node_mixer.h" +#include "quad_files/PID.h" +#include "quad_files/control_algorithm.h" + +double c_controller(int vrpn_id, double vrpn_ts, double set_x, double set_y, double set_z, double set_yaw, + double cur_x, double cur_y, double cur_z, + double cur_phi, double cur_theta, double cur_psi, + double cur_phi_d, double cur_theta_d, double cur_psi_d, + double *z_out, double *y_out, double *x_out, double *yaw_out, + double* pid_y_out, double* pid_roll_out); + +#endif // C_CONTROLLER_H \ No newline at end of file diff --git a/controls/model/loggingAnalysis/logAnalysis.m b/controls/model/loggingAnalysis/logAnalysis.m new file mode 100644 index 0000000000000000000000000000000000000000..ae48f90734c220bf920b8367ca5fca88411d84c7 --- /dev/null +++ b/controls/model/loggingAnalysis/logAnalysis.m @@ -0,0 +1,196 @@ +%% Pull data from model and plot + +% Simulate the model to update parameters +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)); +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); +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); +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_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_value_model_data = yaw_value_model.signals.values(indices_40ms); + +% Pull duty cycle commands from model +PWM0_model = motorCommands.signals.values(indices_40ms, 1); +PWM1_model = motorCommands.signals.values(indices_40ms, 2); +PWM2_model = motorCommands.signals.values(indices_40ms, 3); +PWM3_model = motorCommands.signals.values(indices_40ms, 4); + +%% Plot x control structure + +% Plot lateral controller output +figure(1); subplot(2, 2, 1); +stairs(time, pitch_setpoint, '.-'); hold on; grid minor; +stairs(time_model_40ms, pitch_setpoint_model_data, '.-'); hold off; +title('Lateral Controller Output'); +xlabel('Time (s)'); +ylabel('\theta (rad)'); +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; +title('Pitch Controller Output'); +xlabel('Time (s)'); +ylabel('d\theta/dt (rad/s)'); +legend('Log', 'Model', 'location', 'northwest'); + +% Plot x controller command +subplot(2, 2, 3); +stairs(time, x_command, '.-'); hold on; grid minor; +stairs(time_model_5ms, x_command_model_data, '.-'); hold off; +title('X Command'); +xlabel('Time (s)'); +ylabel('Command'); +legend('Log', 'Model', 'location', 'northwest'); + +% Plot x position +subplot(2, 2, 4); +stairs(time, x_position, '.-'); hold on; grid minor; +stairs(time_model_40ms, x_position_model_data, '.-'); hold off; +title('X Position'); +xlabel('Time (s)'); +ylabel('Position (m)'); +legend('Log', 'Model', 'location', 'northwest'); + +%% Plot y control structure + +% 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; +title('Longitude Controller Output '); +xlabel('Time (s)'); +ylabel('\phi (rad)'); +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; +title('Roll Controller Output'); +xlabel('Time (s)'); +ylabel('d\phi/dt (rad/s)'); +legend('Log', 'Model', 'location', 'northwest'); + +% Plot y controller command +subplot(2, 2, 3); +stairs(time, y_command, '.-'); hold on; grid minor; +stairs(time_model_5ms, y_command_model_data, '.-'); hold off; +title('Y Command'); +xlabel('Time (s)'); +ylabel('Command'); +legend('Log', 'Model', 'location', 'northwest'); + +% Plot y position +subplot(2, 2, 4); +stairs(time, y_position, '.-'); hold on; grid minor; +stairs(time_model_40ms, y_position_model_data, '.-'); hold off; +title('Y Position'); +xlabel('Time (s)'); +ylabel('Position (m)'); +legend('Log', 'Model', 'location', 'northwest'); + +%% Plot z control structure + +% 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; +title('Z Command'); +xlabel('Time (s)'); +ylabel('Command'); +legend('Log', 'Model', 'location', 'northwest'); + +% Plot z position +subplot(2, 1, 2); +stairs(time, z_position, '.-'); hold on; grid minor; +stairs(time_model_40ms, z_position_model_data, '.-'); hold off; +title('Z Position'); +xlabel('Time (s)'); +ylabel('Position (m)'); +legend('Log', 'Model', 'location', 'northwest'); + +%% Plot yaw control structure + +% Plot roll 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; +title('Yaw Controller Output'); +xlabel('Time (s)'); +ylabel('d\psi/dt (rad/s)'); +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; +title('Yaw Command'); +xlabel('Time (s)'); +ylabel('Command'); +legend('Log', 'Model', 'location', 'northwest'); + +% Plot yaw position +subplot(2, 2, 3); +stairs(time, yaw_value, '.-'); hold on; grid minor; +stairs(time_model_40ms, yaw_value_model_data, '.-'); hold off; +title('Yaw Position'); +xlabel('Time (s)'); +ylabel('Value (rad)'); +legend('Log', 'Model', 'location', 'northwest'); + +%% Plot PWM Commands +figure(5); subplot(2, 2, 1); +stairs(time, PWM0,'.-'); hold on; grid minor; +stairs(time_model_40ms, PWM0_model, '.-'); hold off; +title('PWM0 Value'); +xlabel('Time (s)'); +ylabel('PWM0 Command'); +legend('Log', 'Model', 'location', 'northwest'); + +subplot(2, 2, 2); +stairs(time, PWM1,'.-'); hold on; grid minor; +stairs(time_model_40ms, PWM1_model, '.-'); hold off; +title('PWM1 Value'); +xlabel('Time (s)'); +ylabel('PWM1 Command'); +legend('Log', 'Model', 'location', 'northwest'); + +subplot(2, 2, 3); +stairs(time, PWM2,'.-'); hold on; grid minor; +stairs(time_model_40ms, PWM2_model, '.-'); hold off; +title('PWM2 Value'); +xlabel('Time (s)'); +ylabel('PWM2 Command'); +legend('Log', 'Model', 'location', 'northwest'); + +subplot(2, 2, 4); +stairs(time, PWM3,'.-'); hold on; grid minor; +stairs(time_model_40ms, PWM3_model, '.-'); hold off; +title('PWM3 Value'); +xlabel('Time (s)'); +ylabel('PWM3 Command'); +legend('Log', 'Model', 'location', 'northwest'); \ No newline at end of file diff --git a/controls/model/loggingAnalysis/logFiles/logData.csv b/controls/model/loggingAnalysis/logFiles/logData.csv new file mode 100644 index 0000000000000000000000000000000000000000..ec82bdd6374c782adf567e0a0539429ce8758c2d --- /dev/null +++ b/controls/model/loggingAnalysis/logFiles/logData.csv @@ -0,0 +1,404 @@ +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 new file mode 100644 index 0000000000000000000000000000000000000000..b824bc492610e14ccf6acc042a8451f122b98be3 --- /dev/null +++ b/controls/model/loggingAnalysis/logFiles/logData1.csv @@ -0,0 +1,846 @@ +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 new file mode 100644 index 0000000000000000000000000000000000000000..0525f07daba7714fe185e1428a497d0650c1c98c Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/EMLReport/sL897IXghI8zmc3H8vRBKxD.mat 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 new file mode 100644 index 0000000000000000000000000000000000000000..6fa0e5c2e0dcd0882ae2cc364479119d3741f44a Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/info/binfo.mat 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 new file mode 100644 index 0000000000000000000000000000000000000000..57f63efc7757630bf45b1ac51f17b12ba887aa79 --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.c @@ -0,0 +1,1605 @@ +/* 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 new file mode 100644 index 0000000000000000000000000000000000000000..4286ef7247286afaca46e93b22a25d271bb1744e --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.h @@ -0,0 +1,62 @@ +#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 new file mode 100644 index 0000000000000000000000000000000000000000..de1df7ac2e6eb114b8c3ea994643d2e6721d041b Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c15_test_model.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..68e238309af81c569d3346a105eaba55a02dbe5b Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/c_controller.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..97f6b2f0f5d0642552033d2d960abd086de67d00 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/ji/late_c15_sL897IXghI8zmc3H8vRBKxD.mat 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 new file mode 100644 index 0000000000000000000000000000000000000000..5aad425d0f2dc5f80df42e19bd9e1388dbd58f24 --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/multiword_types.h @@ -0,0 +1,283 @@ +#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 new file mode 100644 index 0000000000000000000000000000000000000000..f5f03ffa8a6af6462a49899fefdac93f133d8185 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_add.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..c7b3f5463670414575293d2c769d4e1474c5e6a2 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_bounds.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..3dc3173081aa9f4052c1a945720e3c515ddc9924 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_constant.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..678060b7ce7b9746acba61619839979818b4cce5 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_mixer.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..eb1433a57819b04d777fe3bdf7bb53e50c2b53b7 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/node_pid.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..4e712c27577ba17448ba1cd15dc4115f8a99252c --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypes.h @@ -0,0 +1,59 @@ +#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 new file mode 100644 index 0000000000000000000000000000000000000000..33765b62acae356d99b321e989c3262231895b99 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/rtwtypeschksum.mat 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 new file mode 100644 index 0000000000000000000000000000000000000000..718fd6ff8b46a8bcc8b84837bccb77e49059213d --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.bat @@ -0,0 +1,15 @@ +@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 new file mode 100644 index 0000000000000000000000000000000000000000..37a282f37607e1db89dfb37426d60aedea42b40f --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.c @@ -0,0 +1,362 @@ +/* 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 new file mode 100644 index 0000000000000000000000000000000000000000..7f268eea6059e204d90d40a123b04e0c33a4b704 --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.gmk @@ -0,0 +1,95 @@ +#--------------------------- 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 new file mode 100644 index 0000000000000000000000000000000000000000..5670253ff6dbe2f5639778848c54beb6faea9f40 --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.h @@ -0,0 +1,52 @@ +#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 new file mode 100644 index 0000000000000000000000000000000000000000..6b339f36e8cbb1fa23b17f189510649958aae54d --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.mol @@ -0,0 +1,27 @@ +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 new file mode 100644 index 0000000000000000000000000000000000000000..d4ddc8caec577ec8bf447b339d33b34f6bd23462 Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun.obj 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 new file mode 100644 index 0000000000000000000000000000000000000000..bd991d4b8d54f27595a03c0df12ea4fe92e13cc8 --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_debug_macros.h @@ -0,0 +1,466 @@ + #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 new file mode 100644 index 0000000000000000000000000000000000000000..6bcda9213335be20a9fd24e77d8c10ce166fed0f --- /dev/null +++ b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.c @@ -0,0 +1,287 @@ +#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 new file mode 100644 index 0000000000000000000000000000000000000000..a0a5902cd0297abc1f96246ea25fe03fde04dbdb Binary files /dev/null and b/controls/model/loggingAnalysis/slprj/_sfprj/test_model/_self/sfun/src/test_model_sfun_registry.obj differ diff --git a/controls/model/modelParameters.m b/controls/model/modelParameters.m index e457e0332bd2705446dba5aa74145ebb9f26aeb0..97115a7c498158b6e5d7765cb3de075772fee193 100644 --- a/controls/model/modelParameters.m +++ b/controls/model/modelParameters.m @@ -1,9 +1,14 @@ - % Model Parameters +temp = 0; +% Log Analysis Toggle + logAnalysisToggle = 1; % 1 for log analysis, 0 for normal operation + +% Define Simulink Runtime (if logAnalysisToggle is selected, this will be +% automatically set based on the log files time) + runtime = 20; + +% Model Parameters m = 1.244; % Quadrotor + battery mass g = 9.81; % Acceleration of gravity -% Jxx = 0.0277; % Quadrotor and battery motor of inertia around bx (pitch) -% Jyy = 0.0218; % Quadrotor and battery motor of inertia around by (roll) -% Jzz = 0.0332; % Quadrotor and battery motor of inertia around bz (yaw) 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) @@ -20,16 +25,235 @@ If = 0.511; % Motor internal friction current Pmin = 1e5; % Minimum zybo output duty cycle command Pmax = 2e5; % Maximum zybo output duty cycle command - Tc = 0.01; % Camera system sampling period + 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) x_controlled_o = 0; % Equilibrium lateral controller output y_controlled_o = 0; % Equilibrium longitudinal controller output yaw_controlled_o = 0; % Equilibrium yaw controller output - omega_o = sqrt((m*g)/(4*Kt)); % Equilibrium Rotor Speed + + % Determine Initial Conditions + + % Equilibrium rotor speeds + omega0_o = sqrt((m*g)/(4*Kt)); + omega1_o = sqrt((m*g)/(4*Kt)); + omega2_o = sqrt((m*g)/(4*Kt)); + omega3_o = sqrt((m*g)/(4*Kt)); % Equilibrium height controller output height_controlled_o = (((Rm*If + ... - + (((omega_o * 2 * Rm * Kv * Kq ... + + (((omega0_o * 2 * Rm * Kv * Kq ... * Kd + 1)^2) - 1)/(4* Rm*Kv^2*Kq ... - *Kd))/Vb)*(Pmax- Pmin)+Pmin); \ No newline at end of file + *Kd))/Vb)*(Pmax- Pmin)+Pmin); + + % Equilibrium positions + x_o = 0; + y_o = 0; + z_o = 0; + + % Equilibrium velocities + x_vel_o = 0; + y_vel_o = 0; + z_vel_o = 0; + + % Equilibrium angles + roll_o = 0; + pitch_o = 0; + yaw_o = 0; + + % Equilibrium angular rates + rollrate_o = 0; + 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 + %%%%%% Commented out section until logging is .txt file based %%%%%% + % FNAME + % if you know the name of the log file that you want to parse, set the it + % here only if it is in the working directory. Otherwise, you may leave it + % blank. You will be able to choose the file to parse through an explorer + % window. + % + %fname = 'sampleLogFile.txt'; + fname = 'sampleLogFile.txt'; + fpath = ''; + + if(isempty(fname)) + [fname, fpath] = uigetfile('.txt','Select log file'); + end + + params.file.name = fname; % file name only + params.file.path = fpath; % file path only + params.file.pathName = [fpath fname]; % file path with file name + + [dataStruct, headers] = parse_log_model(params.file.pathName); + + time = dataStruct.Time.data; + runtime = max(time); + + % Determine x position error + x_setpoint = dataStruct.X_Setpoint_Constant.data; + x_position = dataStruct.VRPN_X_Constant.data; + x_error = timeseries(x_setpoint - x_position, time); + + % Determine y position error + y_setpoint = dataStruct.Y_Setpoint_Constant.data; + y_position = dataStruct.VRPN_Y_Constant.data; + y_error = timeseries(y_setpoint - y_position, time); + + % Determine z position error + z_setpoint = dataStruct.Z_Setpoint_Constant.data; + z_position = dataStruct.VRPN_Z_Constant.data; + z_error = timeseries(z_setpoint - z_position, time); + + % Determine pitch error + pitch_setpoint = dataStruct.X_pos_PID_Correction.data; + pitch_value = dataStruct.VRPN_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_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 = zeros(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 = dataStruct.Pitch_PID_Correction.data; + pitchrate_value = dataStruct.gyro_y.data; + pitchrate_error = timeseries(pitchrate_setpoint - pitchrate_value, time); + + % Determine roll rate error + rollrate_setpoint = dataStruct.Roll_PID_Correction.data; + rollrate_value = dataStruct.gyro_x.data; + rollrate_error = timeseries(rollrate_setpoint - rollrate_value, time); + + % Determine yaw rate error + yawrate_setpoint = dataStruct.Yaw_PID_Correction.data; + yawrate_value = dataStruct.gyro_z.data; + yawrate_error = timeseries(yawrate_setpoint - yawrate_value, time); + + % Pull motor commands from log + x_command = dataStruct.Pitch_Rate_PID_Correction; + y_command = dataStruct.Roll_Rate_PID_Correction; + z_command = dataStruct.Altitude_PID_Correction; + yaw_command = dataStruct.Yaw_Rate_PID_Correction; + + % Determine signal mix PWM values + PWM0 = dataStruct.Signal_Mixer_PWM_0.data; + PWM1 = dataStruct.Signal_Mixer_PWM_1.data; + PWM2 = dataStruct.Signal_Mixer_PWM_2.data; + PWM3 = dataStruct.Signal_Mixer_PWM_3.data; + +end + + diff --git a/controls/model/parse_log_model.m b/controls/model/parse_log_model.m new file mode 100644 index 0000000000000000000000000000000000000000..9fba92fa6d0d3d670370b06a035fd9ee802698d2 --- /dev/null +++ b/controls/model/parse_log_model.m @@ -0,0 +1,111 @@ +function [loggedData, headers] = parse_log_model(filename, params, expData) +%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 +% params - this is the params structure which holds the analysis +% configuration options + +% Check if file exists +if (~exist(filename,'file')) + error(strcat(filename, ' does not exist')); +end + +% Open file +FileID = fopen(filename, 'r'); + +% Gets the first line of the file +string = fgetl(FileID); + +% Test first line, if not formatted correctly, reject +if(size(regexp(string, '^#')) == 0) + error(strcat(filename, ' is not properly formatted, and does not contain "#" headers')); +end + +% Loop through header lines +while( regexp(string, '^#') == 1 ) + + %Print out string and move on + disp(string) + old = string; + string = fgetl(FileID); + +end + +% Two possibilities for the next two lines: +% 1) line of headers +% 2) line of units +foundHeaders = 0; +foundUnits = 0; + +% Checking current line's type: +identifier = string(1); + +if (regexp(identifier,'%')) + foundHeaders = 1; + % this is a line of headers; extract headers: + headers = strsplit(string); + headers{1} = strrep(headers{1},'%', ''); + numOfHeaders = length(headers); +else + if (regexp(identifier,'&')) + foundUnits = 1; + % this is a line of units; extract units: + units = strsplit(string); + units{1} = strrep(units{1},'&',''); + else + error(strcat(filename, ' is not properly formatted, contains undefined line identifier.')); + end +end + +% Obtaining the next line +string = fgetl(FileID); +identifier = string(1); + +if(foundHeaders) + if(regexp(identifier,'&')) + foundUnits = 1; + % this is a line of units; extract units: + units = strsplit(string); + units{1} = strrep(units{1},'&',''); + else + error(strcat(filename, ' is not properly formatted, contains or undefined/excessive line identifiers.')); + end +else + if(foundUnits) + if(regexp(identifier,'%')) + % this is a line of headers; extract headers: + headers = strsplit(string); + headers{1} = strrep(headers{1},'%', ''); + numOfHeaders = length(headers); + end + else + error('Should never be able to get here'); + end +end + +% sanity check and clean up +if(numOfHeaders ~= length(units)) + error(strcat(filename, ' is not properly formatted, contains unmatched number of units and headers')); +end +clear foundHeaders foundUnits; + +% Get all data into a single matrix called "log" +log = []; +line = zeros(1,numOfHeaders); +while ~feof(FileID) + line = textscan(FileID, '%f', numOfHeaders); + line = transpose(cell2mat(line)); + log = [log;line]; +end + +% Converting the log matrix into a expData structure. +for i = 1:numOfHeaders + + eval(['loggedData.' headers{i} '.data = log(:,i);']); % adding data + eval(['loggedData.' headers{i} '.unit = cell2mat(units(i));']); % adding unit + +end + + +end + diff --git a/controls/model/quad_files/.gitignore b/controls/model/quad_files/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..1c4bc674e912af84e9c6bed639cd5780a68b7846 --- /dev/null +++ b/controls/model/quad_files/.gitignore @@ -0,0 +1,3 @@ +# Don't track the copied files here +*.h +*.c \ No newline at end of file diff --git a/controls/model/quad_files/copy_files.bat b/controls/model/quad_files/copy_files.bat new file mode 100644 index 0000000000000000000000000000000000000000..bd5f65861b103ddaf3b761a47c9bc584bb35b50b --- /dev/null +++ b/controls/model/quad_files/copy_files.bat @@ -0,0 +1,27 @@ +copy ..\..\..\quad\computation_graph\src\computation_graph.c computation_graph.c +copy ..\..\..\quad\computation_graph\src\computation_graph.h computation_graph.h + +copy ..\..\..\quad\sw\modular_quad_pid\src\control_algorithm.h control_algorithm.h +copy ..\..\..\quad\sw\modular_quad_pid\src\control_algorithm.c control_algorithm.c + +copy ..\..\..\quad\sw\modular_quad_pid\src\PID.h PID.h +copy ..\..\..\quad\sw\modular_quad_pid\src\type_def.h type_def.h +copy ..\..\..\quad\sw\modular_quad_pid\src\sensor_processing.h sensor_processing.h +copy ..\..\..\quad\sw\modular_quad_pid\src\log_data.h log_data.h +copy ..\..\..\quad\sw\modular_quad_pid\src\quadposition.h quadposition.h +copy ..\..\..\quad\sw\modular_quad_pid\src\util.h util.h +copy ..\..\..\quad\sw\modular_quad_pid\src\timer.h timer.h +copy ..\..\..\groundStation\src\backend\commands.h commands.h +copy ..\..\..\groundStation\src\backend\callbacks.h callbacks.h + +mkdir graph_blocks +copy ..\..\..\quad\computation_graph\src\graph_blocks\node_constant.h graph_blocks\node_constant.h +copy ..\..\..\quad\computation_graph\src\graph_blocks\node_constant.c graph_blocks\node_constant.c +copy ..\..\..\quad\computation_graph\src\graph_blocks\node_add.h graph_blocks\node_add.h +copy ..\..\..\quad\computation_graph\src\graph_blocks\node_add.c graph_blocks\node_add.c +copy ..\..\..\quad\sw\modular_quad_pid\src\graph_blocks\node_mixer.c graph_blocks\node_mixer.c +copy ..\..\..\quad\sw\modular_quad_pid\src\graph_blocks\node_mixer.h graph_blocks\node_mixer.h +copy ..\..\..\quad\sw\modular_quad_pid\src\graph_blocks\node_pid.c graph_blocks\node_pid.c +copy ..\..\..\quad\sw\modular_quad_pid\src\graph_blocks\node_pid.h graph_blocks\node_pid.h +copy ..\..\..\quad\sw\modular_quad_pid\src\graph_blocks\node_bounds.c graph_blocks\node_bounds.c +copy ..\..\..\quad\sw\modular_quad_pid\src\graph_blocks\node_bounds.h graph_blocks\node_bounds.h \ No newline at end of file diff --git a/controls/model/test_model.slx b/controls/model/test_model.slx index 805e43a9e1d83040c87b713476195126ca17d371..56975e7eba373b73a005d9451ddcb553bd36f882 100644 Binary files a/controls/model/test_model.slx and b/controls/model/test_model.slx differ diff --git a/groundStation/Makefile b/groundStation/Makefile index 873685d62b5d7f3499fc6e3c0806f5475f67fd46..c6ea99f3502e19309fe8cf0800b0440ed920c3e7 100644 --- a/groundStation/Makefile +++ b/groundStation/Makefile @@ -6,10 +6,15 @@ GXX=g++ CFLAGS= -Wall -pedantic -Wextra -Werror -std=gnu99 -g -Wno-unused-parameter -Wno-unused-variable -Wno-unused-function -Wno-unused-but-set-variable CXXFLAGS= -Wall -pedantic -Wextra -Werror -Wno-reorder -Wno-unused-variable -std=c++0x -g INCLUDES = $(foreach dir, $(INCDIR), -I$(dir)) -INCDIR=inc src/vrpn src/vrpn/quat src/vrpn/build $(BESRCDIR) $(CLISRCDIR) $(FESRCDIR) +INCDIR=inc src/vrpn src/vrpn/quat src/vrpn/build $(COMSRCDIR) $(BESRCDIR) $(CLISRCDIR) $(FESRCDIR) LIBS= -lpthread -lbluetooth -lvrpn -lquat -Lsrc/vrpn/build -Lsrc/vrpn/build/quat OBJDIR=obj +# Common Objects +COMSRCDIR=../common +COMSOURCES := $(wildcard $(COMSRCDIR)/*.c ) +COMOBJECTS = $(COMSOURCES:$(COMSRCDIR)/%.c=$(OBJDIR)/%.o) + # Backend Specific Variables BEBINARY=BackEnd BESRCDIR=src/backend @@ -31,7 +36,7 @@ FECSOURCES := $(wildcard $(FESRCDIR)/*.c ) FECOBJECTS = $(FECSOURCES:$(FESRCDIR)/%.c=$(OBJDIR)/%.o) -OBJECTS= $(CLIOBJECTS) $(BECOBJECTS) $(BECPPOBJECTS) $(FECOBJECTS) +OBJECTS= $(COMOBJECTS) $(CLIOBJECTS) $(BECOBJECTS) $(BECPPOBJECTS) $(FECOBJECTS) # Default target all: logs objdir backend cli $(SYMLINKS) frontend.a @@ -51,9 +56,12 @@ $(CLIOBJECTS) : $(OBJDIR)/%.o : $(CLISRCDIR)/%.c $(GCC) $(CFLAGS) -c $^ -o $@ $(INCLUDES) $(LIBS) -backend: $(BECPPOBJECTS) $(BECOBJECTS) +backend: $(COMOBJECTS) $(BECPPOBJECTS) $(BECOBJECTS) $(GXX) $(CXXFLAGS) $^ -o $(BEBINARY) $(INCLUDES) $(LIBS) +$(COMOBJECTS) : $(OBJDIR)/%.o : $(COMSRCDIR)/%.c + $(GCC) $(CFLAGS) -c $^ -o $@ $(INCLUDES) $(LIBS) + $(FECOBJECTS) : $(OBJDIR)/%.o : $(FESRCDIR)/%.c $(GCC) $(CFLAGS) -c $^ -o $@ $(INCLUDES) $(LIBS) @@ -80,4 +88,4 @@ clean: rm -rf $(OBJDIR)/ $(BEBINARY) $(CLIBINARY) debug: - @echo $(OBJECTS) + @echo $(COMOBJECTS) diff --git a/groundStation/src/backend/backend.c b/groundStation/src/backend/backend.c index 7b1a01f75b1cd2a1e400277d188069d87a3abe8a..cdd0727a269d0d857fc13be51f6a2e04696c21ae 100644 --- a/groundStation/src/backend/backend.c +++ b/groundStation/src/backend/backend.c @@ -29,17 +29,15 @@ #include <netinet/tcp.h> //user created includes -#include "communication.h" -#include "commands.h" +#include "../../../common/commands.h" #include "vrpn_tracker.hpp" #include "type_def.h" #include "packet.h" -#include "responseparam.h" +#include "param.h" #include "update.h" #include "config.h" -#include "cmHandler.h" -#include "getparam.h" -#include "setparam.h" +#include "source.h" +#include "output.h" #include "bitwise.h" #define QUAD_BT_ADDR "00:06:66:64:61:D6" @@ -82,7 +80,7 @@ static void quad_recv(); /* Checks to see if socket has disconnected. Returns 1 on disconnect, else returns 0 */ static int wasDisconnected(int fd); /* handle controller responses from quad to frontend */ -static void handleResponseParam(struct metadata *m, uint8_t * data); +static void handleResponse(struct metadata *m, uint8_t * data); /* Thread-safe wrappers */ @@ -629,8 +627,18 @@ static void client_recv(int fd) { buffer[newline] = '\0'; printf("Client(%d) : '%s'\n",fd, buffer); - struct controller_message cm; - if (stringToCm(buffer, &cm) == NULL) { + char * first_word; + char * tmp = strdup(buffer); + first_word = strtok(tmp, " "); + free(tmp); + + ssize_t msg_type, i; + for (i = 0; i < MAX_TYPE_ID; ++i) { + if ((msg_type = findCommand(first_word)) != -1) + break; + } + + if (msg_type == -1) { /* buffer was not a quad command, handling internally to * backend instead of forwarding to quad */ @@ -668,14 +676,32 @@ static void client_recv(int fd) { uint8_t packet[64]; struct metadata m; uint8_t data[128]; - ssize_t result; - - if (strncmp(buffer, "set", 3) == 0) { - result = EncodeSetparam(&m, data, 128, &cm); - } else if (strncmp(buffer, "get", 3) == 0) { - result = EncodeGetparam(&m, data, 128, &cm); - } else { - warnx("not implemented yet"); + ssize_t result; + ssize_t psize; + + switch (msg_type) { + case SETPARAM_ID: + result = EncodeSetParam(&m, data, 128, buffer); + break; + case GETPARAM_ID: + result = EncodeGetParam(&m, data, 128, buffer); + break; + case SETSOURCE_ID: + result = EncodeSetSource(&m, data, 128, buffer); + break; + case GETSOURCE_ID: + result = EncodeGetSource(&m, data, 128, buffer); + break; + case GETOUTPUT_ID: + result = EncodeGetOutput(&m, data, 128, buffer); + break; + case GETNODES_ID: + result = -1; + // result = EncodeGetnodes(&m, data, 128, buffer); + break; + default: + result = -1; + break; } if (result < 0) { @@ -683,16 +709,15 @@ static void client_recv(int fd) { return; } - ssize_t psize; + m.msg_id = currMessageID++; + if ((psize = EncodePacket(packet, 64, &m, data)) < 0) { warnx("Big problems. client_recv. EncodePacket"); return; } - m.msg_id = currMessageID++; - /* Only add the client to the pending responses if it was a getparam command */ - if (m.msg_type == GETPARAM_ID) { + if (m.msg_type == GETPARAM_ID || m.msg_type == GETOUTPUT_ID || m.msg_type == GETSOURCE_ID) { if (clientAddPendResponses(fd, BytesTo16(packet[ID_L], packet[ID_H])) == -1) { warnx("Ran out of room! Consider increasing CLIENT_MAX_PENDING_RESPONSES!\n"); } @@ -778,52 +803,52 @@ static void quad_recv() { respBufLen -= packetlen; switch (m.msg_type) { - case DEBUG_ID : - case PACKETLOG_ID : - case GETPACKETLOGS_ID : - case UPDATE_ID : - case BEGINUPDATE_ID : - printf("(Backend): Command '%s' ignored\n", MessageTypes[m.msg_type].cmdText); - break; case LOG_ID: /* something like this */ printf("(Quad) : Log found\n"); fwrite((char *) data, sizeof(char), m.data_len, quadlog_file); // fflush(quadlog_file); break; - case RESPONSE_ID: - printf("(Backend): response id found\n"); - break; - case SETPARAM_ID: - case GETPARAM_ID: - printf("(Backend): Command '%s' ignored\n", MessageTypes[m.msg_type].cmdText); - break; case RESPPARAM_ID: - handleResponseParam(&m, data); + case RESPSOURCE_ID: + case RESPOUTPUT_ID: + handleResponse(&m, data); break; + case RESPNODES_ID: default: - printf("(Backend): message type %d unrecognized\n", m.msg_type); + printf("(Backend): message type %d ignored from quad\n", m.msg_type); } } } -static void handleResponseParam(struct metadata *m, uint8_t * data) +static void handleResponse(struct metadata *m, uint8_t * data) { - struct controller_message cm; - if (DecodeResponseParam(&cm, m, data) < 0) { - warnx("DecodeResponse error"); - return; - } + ssize_t result; char buffer[128]; - const char * message = cmToString(RESPPARAM_ID, &cm); + switch (m->msg_type) { + case RESPPARAM_ID: + result = DecodeResponseParam(buffer, m, data); + break; + case RESPSOURCE_ID: + result = DecodeResponseSource(buffer, m, data); + break; + case RESPOUTPUT_ID: + result = DecodeResponseOutput(buffer, m, data); + break; + default: + result = -1; + } - size_t len = snprintf(buffer, 128, "%s %f\n", message, cm.value); + if (result < 0) { + warnx("DecodeResponse error"); + return; + } for(int fd = 0; fd <= max_fd; ++fd) { - if (get_client_index(fd) > -1) { + if (get_client_index(fd) < 0) { clientRemovePendResponses(fd, m->msg_id); - write(fd, buffer, len); + write(fd, buffer, result); } } } diff --git a/groundStation/src/backend/callbacks.c b/groundStation/src/backend/callbacks.c index a47d521f24cb456858c7de567274caee82951023..875167b483adc933f8dfcc57507a84a0b6c936ae 100644 --- a/groundStation/src/backend/callbacks.c +++ b/groundStation/src/backend/callbacks.c @@ -1,378 +1,3 @@ #include "commands.h" /* New stuff - this is nice and clean */ - -/* Override any callbacks here */ - - -/****** LEGACY CODE BE VERY AFRAID ********/ - -// TAKE THESE OUT WHEN IMPLEMENTING ON THE QUAD SIDE -float getFloat(unsigned char* str, int pos) { - union { - float f; - int i; - } x; - x.i = ((str[pos+3] << 24) | (str[pos+2] << 16) | (str[pos+1] << 8) | (str[pos])); - return x.f; -} - -int getInt(unsigned char* str, int pos) { - int i = ((str[pos+3] << 24) | (str[pos+2] << 16) | (str[pos+1] << 8) | (str[pos])); - return i; -} -//------------------------------------------------ - -int cb_debug(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for debug\n"); - return 0; -} - -int cb_update(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - unsigned char update[28]; - memcpy(update, ((float *)packet), 28); - - int packetId = getInt(update, 0); - float y_pos = getFloat(update, 4); - float x_pos = getFloat(update, 8); - float alt_pos = getFloat(update, 12); - float roll = getFloat(update, 16); - float pitch = getFloat(update, 20); - float yaw = getFloat(update, 24); - - structs->log_struct.currentQuadPosition.packetId = packetId; - structs->log_struct.currentQuadPosition.y_pos = y_pos; - structs->log_struct.currentQuadPosition.x_pos = x_pos; - structs->log_struct.currentQuadPosition.alt_pos = alt_pos; - structs->log_struct.currentQuadPosition.roll = roll; - structs->log_struct.currentQuadPosition.pitch = pitch; - structs->log_struct.currentQuadPosition.yaw = yaw; - - printf("QUAD: VRPN Packet:"); - printf("Packet ID: %d\n", packetId); - printf("Y Position: %f\n", y_pos); - printf("X Position: %f\n", x_pos); - printf("Altitude Position: %f\n", alt_pos); - printf("Roll: %f\n", roll); - printf("Pitch: %f\n", pitch); - printf("Yaw: %f\n", yaw); - - printf("function for update\n"); - return 0; -} - -// Why is this here? -// This should be on the ground station side -int logdata(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("Logging: %s\n", packet); - return 0; -} - -int response(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("This is the response: %s\n", packet); - - return 0; -} - -// ------------------------------------------------------------------ - -int setyaw(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - - printf("%f\n", value); - - structs->setpoint_struct.desiredQuadPosition.yaw = value; - - printf("function for setyaw: %f\n", structs->setpoint_struct.desiredQuadPosition.yaw); - - return 0; -} - -int setyawp(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.yaw_angle_pid.Kp = value; - - printf("function for setyawp: %f\n", structs->parameter_struct.yaw_angle_pid.Kp); - - return 0; -} - -int setyawd(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.yaw_angle_pid.Kd = value; - - printf("function for setyawd: %f\n", structs->parameter_struct.yaw_angle_pid.Kd); - - return 0; -} - -int setroll(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->setpoint_struct.desiredQuadPosition.roll = value; - - printf("function for setroll: %f\n", structs->setpoint_struct.desiredQuadPosition.roll); - - return 0; -} - -int setrollp(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.local_y_pid.Kp = value; - - printf("function for setrollp: %f\n", structs->parameter_struct.local_y_pid.Kp); - - return 0; -} - -int setrolld(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.local_y_pid.Kd = value; - - printf("function for setrolld: %f\n", structs->parameter_struct.local_y_pid.Kd); - - return 0; -} - -int setpitch(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->setpoint_struct.desiredQuadPosition.pitch = value; - - printf("function for setpitch: %f\n", structs->setpoint_struct.desiredQuadPosition.pitch); - - return 0; -} - -int setpitchp(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.local_x_pid.Kp = value; - - printf("function for setpitchp: %f\n", structs->parameter_struct.local_x_pid.Kp); - - return 0; -} - -int setpitchd(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.local_x_pid.Kd = value; - - printf("function for setpitchd: %f\n", structs->parameter_struct.local_x_pid.Kd); - - return 0; -} - -// ------------------------------------------------------------ -// These should be renamed to altitude! -int setthrottle(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->setpoint_struct.desiredQuadPosition.alt_pos = value; - - printf("function for setthrottle: %f\n", structs->setpoint_struct.desiredQuadPosition.alt_pos); - - return 0; -} - -int setthrottlep(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.alt_pid.Kp = value; - - printf("function for setthrottlep: %f\n", structs->parameter_struct.alt_pid.Kp); - - return 0; -} - -int setthrottlei(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.alt_pid.Ki = value; - - printf("function for setthrottlei: %f\n", structs->parameter_struct.alt_pid.Ki); - - return 0; -} - -int setthrottled(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - float value; - - memcpy(&value, ((float *)packet), dataLen); - structs->parameter_struct.alt_pid.Kd = value; - - printf("function for setthrottled: %f\n", structs->parameter_struct.alt_pid.Kd); - - return 0; -} -int getyaw(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getyawp(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getyawd(unsigned char *packet, int dataLen, modular_structs_t *structs) { - return 0; -} -int getroll(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getrollp(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getrolld(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getpitch(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getpitchp(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getpitchd(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getthrottle(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getthrottlep(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getthrottlei(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int getthrottled(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} - -// These should be renamed to altitude! -// ------------------------------------------------------------ - - - - -int getgyro(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for getgyro\n"); - return 0; -} - -int getpitchangle(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for getpitchangle\n"); - return 0; -} - -int getrollangle(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for getrollangle\n"); - return 0; -} - - -int getaccel(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for getaccel\n"); - return 0; -} - - -int respgyro(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for respgyro\n"); - return 0; -} - -int resppitchangle(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for resppitchangle\n"); - return 0; -} - -int resprollangle(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for resprollangle\n"); - return 0; -} - - -int respaccel(unsigned char *packet, int dataLen, modular_structs_t *structs) -{ - printf("function for respaccel\n"); - return 0; -} - -int respyaw(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int respyawp(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int respyawd(unsigned char *packet, int dataLen, modular_structs_t *structs) { - return 0; -} -int resproll(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int resprollp(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int resprolld(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int resppitch(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int resppitchp(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int resppitchd(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int respthrottle(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int respthrottlep(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int respthrottlei(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} -int respthrottled(unsigned char *packet, int dataLen, modular_structs_t *structs){ - return 0; -} diff --git a/groundStation/src/backend/callbacks.h b/groundStation/src/backend/callbacks.h index 69510e0a8165c7cc99f99a8e4aeb7e6eab3ffb0c..cc5fd8cabe8e5655b318df854b0731646076c4d2 100644 --- a/groundStation/src/backend/callbacks.h +++ b/groundStation/src/backend/callbacks.h @@ -7,6 +7,4 @@ /* Make commands.c happy */ typedef void (command_cb)(void); -float getFloat(unsigned char * str, int pos); - #endif /* __CALLBACKS_H */ diff --git a/groundStation/src/backend/cmHandler.c b/groundStation/src/backend/cmHandler.c deleted file mode 100644 index a1159c1838d7803902c96aa41097b83dbf68ffce..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/cmHandler.c +++ /dev/null @@ -1,185 +0,0 @@ -#include <stdlib.h> - -#include "cmHandler.h" - -const char * respParamStrings[MAX_PARAM_COMMANDS] = { - "getrollp", - "getrolli", - "getrolld", - "getpitchp", - "getpitchi", - "getpitchd", - "getyawp", - "getyawi", - "getyawd", - "getrollratep", - "getrollratei", - "getrollrated", - "getpitchratep", - "getpitchratei", - "getpitchrated", - "getyawratep", - "getyawratei", - "getyawrated", - "getlatp", - "getlati", - "getlatd", - "getlongp", - "getlongi", - "getlongd", - "getheightp", - "getheighti", - "getheightd", - "getlat", - "getlong", - "getheight" -}; - -const char * setParamStrings[MAX_PARAM_COMMANDS] = { - "setrollp", - "setrolli", - "setrolld", - "setpitchp", - "setpitchi", - "setpitchd", - "setyawp", - "setyawi", - "setyawd", - "setrollratep", - "setrollratei", - "setrollrated", - "setpitchratep", - "setpitchratei", - "setpitchrated", - "setyawratep", - "setyawratei", - "setyawrated", - "setlatp", - "setlati", - "setlatd", - "setlongp", - "setlongi", - "setlongd", - "setheightp", - "setheighti", - "setheightd", - "setlat", - "setlong", - "setheight", -}; - -const char * cmToString(int msgType, const struct controller_message *cm) -{ - size_t index; - if (cm->id == X_SETPOINT_ID) { - index = PARAM_LOCAL_X; // This will change when we make node structure changes - } else if (cm->id == X_SETPOINT_ID) { - index = PARAM_LOCAL_Y; // This will change when we make node structure changes - } else if (cm->id == X_SETPOINT_ID) { - index = PARAM_ALT; // This will change when we make node structure changes - } else { - index = (cm->id * MAX_CONTROL_PARAM_ID) + cm->value_id; - } - switch (msgType) { - case DEBUG_ID : - case PACKETLOG_ID : - case GETPACKETLOGS_ID : - case UPDATE_ID : - case BEGINUPDATE_ID : - case LOG_ID: - case SETPARAM_ID: - return setParamStrings[index]; - case GETPARAM_ID: - return NULL; - break; - case RESPONSE_ID: - return NULL; - case RESPPARAM_ID: - return respParamStrings[index]; - default: - return NULL; - break; - } -} - -struct controller_message * stringToCm(const char * string, struct controller_message *cm) -{ - int result; - size_t i; - char cmdString[strlen(string)]; - strncpy(cmdString, string, strlen(string)); - - float cmdValue; - for (i = 0; i < strlen(string) + 1; ++i) { - if (string[i] == ' ' || string[i] == '\n' || string[i] == '\0') { - cmdString[i] = '\0'; - break; - } - } - - int index = -1; - - for(i = 0; i < MAX_PARAM_COMMANDS; ++i) { - - if((result = strncmp(cmdString, respParamStrings[i], strlen(respParamStrings[i]))) == 0 && - strlen(cmdString) == strlen(respParamStrings[i])) { - index = i; - break; - } else if ((result = strncmp(cmdString, setParamStrings[i], strlen(setParamStrings[i]))) == 0 && - strlen(cmdString) == strlen(setParamStrings[i])) { - cm->value = strtof(&string[strlen(cmdString)],NULL); - index = i; - break; - } - } - // printf("index = %d\n", index); - - /* Error, nothing found */ - if (index == -1) { - return NULL; - } else { - cm->value_id = i % MAX_CONTROL_PARAM_ID; // Default assuming not a setpoint command - if (i <= PARAM_ROLL_D) { - - cm->id = ROLL_ID; - } else if (i <= PARAM_PITCH_D) { - - cm->id = PITCH_ID; - } else if (i <= PARAM_YAW_D) { - - cm->id = YAW_ID; - } else if (i <= PARAM_ROLL_RATE_D) { - - cm->id = ROLL_RATE_ID; - } else if (i <= PARAM_PITCH_RATE_D) { - - cm->id = PITCH_RATE_ID; - } else if (i <= PARAM_YAW_RATE_D) { - - cm->id = YAW_RATE_ID; - } else if (i <= PARAM_LOCAL_X_D) { - - cm->id = LOCAL_X_ID; - } else if (i <= PARAM_LOCAL_Y_D) { - - cm->id = LOCAL_Y_ID; - } else if (i <= PARAM_ALT_D) { - - cm->id = ALT_ID; - } else if ( i == PARAM_LOCAL_X) { - - cm->id = X_SETPOINT_ID; - cm->value_id = 0; - } else if ( i == PARAM_LOCAL_Y) { - - cm->id = Y_SETPOINT_ID; - cm->value_id = 0; - } else if ( i == PARAM_ALT) { - - cm->id = ALT_SETPOINT_ID; - cm->value_id = 0; - } - } - // printf("cm->id = %d\ncm->value_id = %d\n", cm->id, cm->value_id); - return cm; -} \ No newline at end of file diff --git a/groundStation/src/backend/cmHandler.h b/groundStation/src/backend/cmHandler.h deleted file mode 100644 index f2761aa9b60ccbee08e699e6a035900e08e52cc3..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/cmHandler.h +++ /dev/null @@ -1,48 +0,0 @@ -#ifndef _CMHANDLER_H -#define _CMHANDLER_H - -#include "controller.h" - -enum paramIndices { - PARAM_ROLL_P , - PARAM_ROLL_I , - PARAM_ROLL_D , - PARAM_PITCH_P , - PARAM_PITCH_I , - PARAM_PITCH_D , - PARAM_YAW_P , - PARAM_YAW_I , - PARAM_YAW_D , - PARAM_ROLL_RATE_P, - PARAM_ROLL_RATE_I, - PARAM_ROLL_RATE_D, - PARAM_PITCH_RATE_P, - PARAM_PITCH_RATE_I, - PARAM_PITCH_RATE_D, - PARAM_YAW_RATE_P, - PARAM_YAW_RATE_I, - PARAM_YAW_RATE_D, - PARAM_LOCAL_X_P , - PARAM_LOCAL_X_I , - PARAM_LOCAL_X_D , - PARAM_LOCAL_Y_P , - PARAM_LOCAL_Y_I , - PARAM_LOCAL_Y_D , - PARAM_ALT_P, - PARAM_ALT_I, - PARAM_ALT_D, - PARAM_LOCAL_X , - PARAM_LOCAL_Y , - PARAM_ALT , - MAX_PARAM_COMMANDS -}; - -extern const char * respParamStrings[MAX_PARAM_COMMANDS]; - -extern const char * setParamStrings[MAX_PARAM_COMMANDS]; - -const char * cmToString(int msgType, const struct controller_message *cm); - -struct controller_message * stringToCm(const char * string, struct controller_message *cm); - -#endif /* _CMHANDLER_H */ \ No newline at end of file diff --git a/groundStation/src/backend/communication.c b/groundStation/src/backend/communication.c deleted file mode 100644 index a6f14f29c36501907bee69b479b6541c2fe1fdf3..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/communication.c +++ /dev/null @@ -1,95 +0,0 @@ -#include "communication.h" -#include "commands.h" -#include <string.h> -#include <ctype.h> - -static int msgNum = 0; -//-------------------------------- -// Ground Station -//-------------------------------- - -// Formatting commands from ground station CLI -int formatCommand(char *command, unsigned char *formattedCommand) { - // fprintf(stderr, "length = %li , received '%s'\n", strlen(command), command); - char cmd[512]; - strncpy(cmd, command, 512); - - char * cmdText = strtok(cmd, " "); - - return -1; -} - -// returns the length of the data in bytes (datalen from packet) and fills data -// and metadata with the packet information -// use as follows: -// -// packet is the entire packet message (formatted) -// data is an unallocated (char *) (pass it to this function as &data) -// meta_data is a pointer to an instance of metadata_t -// -int parse_packet(unsigned char * packet, unsigned char * data, metadata_t * meta_data) -{ - //---------------------------------------------------------------------------------------------- - // index|| 0 | 1 | 2 | 3 & 4 | 5 & 6 | 7+ | end | - //---------------------------------------------------------------------------------------------| - // msg param|| beg char | msg type | msg id | data len (bytes) | data | checksum | - //-------------------------------------------------------------------------------------------- | - // bytes|| 1 | 1 | 1 | 2 | 2 | var | 1 | - //---------------------------------------------------------------------------------------------- - - // first byte must be the begin char - if(packet[0] != 0xBE) - return -1; - - // receive metadata - meta_data->begin_char = packet[0]; - meta_data->msg_type = packet[2] << 8 | packet[1]; - meta_data->msg_id = (packet[4] << 8) | (packet[3]); - meta_data->data_len = (packet[6] << 8) | (packet[5]); - unsigned char packet_checksum = packet[7+meta_data->data_len]; - //fprintf(stderr, "datalen: %d\n", meta_data->data_len); - - int i; - - // receive data - for(i = 0; i < meta_data->data_len; i++) - { - data[i] = packet[7+i]; - } - - // calculate checksum - unsigned char calculated_checksum = 0; - for(i = 0; i < meta_data->data_len + 7 - 1; i++) - { - calculated_checksum ^= packet[i]; - } - - // compare checksum - if(packet_checksum != calculated_checksum) { - return -2; - } - - return 0; -} - -// Process the command received -int processCommand(unsigned char *packet, modular_structs_t *structs) { - int validPacket; - unsigned char data[256]; - metadata_t metadata; - - // Validate the message is correctly formatted - validPacket = parse_packet(packet, data, &metadata); - if(validPacket != 0) { - return -1; - } - - if(metadata.data_len >= 0) { - (* (MessageTypes[(unsigned char)metadata.msg_type].functionPtr))(); - - return 0; - } - - // Only gets here if there is an error - return -1; -} diff --git a/groundStation/src/backend/communication.h b/groundStation/src/backend/communication.h deleted file mode 100644 index f3439f26605357edb7b6575cabfce8ffc6fdb36d..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/communication.h +++ /dev/null @@ -1,16 +0,0 @@ -#ifndef __COMMUNICATION_H -#define __COMMUNICATION_H - -#include <stdio.h> -#include <string.h> -#include <stdlib.h> -#include <limits.h> -#include "type_def.h" - -int formatCommand(char *command, unsigned char *formattedCommand); -int formatPacket(metadata_t *metadata, void *data, unsigned char *formattedCommand); -int parse_packet(unsigned char * packet, unsigned char * data, metadata_t * meta_data); -int processCommand(unsigned char *command, modular_structs_t *structs); -int logData(unsigned char *log_msg, unsigned char *formattedCommand); - -#endif /* __COMMUNICATION_H */ diff --git a/groundStation/src/backend/controller.h b/groundStation/src/backend/controller.h deleted file mode 100644 index 13d12353c464de6aeb89e7ea36340af2788770ff..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/controller.h +++ /dev/null @@ -1,34 +0,0 @@ -#ifndef _controller_h -#define _controller_h - - -/* For now, the enums come from commands.h */ -#include "commands.h" -#if 0 -enum ControllerID { - ROLL_ID, // 00 - Roll PID - PITCH_ID, // 01 - Pitch PID - YAW_ID, // 02 - Yaw PID - ROLL_RATE_ID, // 03 - Roll rate PID - PITCH_RATE_ID, // 04 - Pitch rate PID - YAW_RATE_ID, // 05 - Yaw rate PID - LOCAL_X_ID, // 06 - Local X PID - LOCAL_Y_ID, // 07 - Local Y PID - ALT_ID, // 08 - Altitude PID -}; - -enum ControllerValueID{ - KP_ID, // 00 - P constant - KI_ID, // 01 - I constant - KD_ID, // 02 - D constant - SP_ID, // 03 - Setpoint value -}; -#endif - -struct controller_message { - enum ControllerID id; - enum ControlParamID value_id; - float value; -}; - -#endif diff --git a/groundStation/src/backend/getparam.c b/groundStation/src/backend/getparam.c deleted file mode 100644 index 98580741766e6187596c4519b6a8f3e2d1c0d3f5..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/getparam.c +++ /dev/null @@ -1,54 +0,0 @@ -#include "getparam.h" -#include "commands.h" -#include "bitwise.h" - -#include <sys/types.h> - -enum GetparamData { - CTRL_ID, - CTRLVAL_ID, - GP_DATA_SIZE -}; - -/* Creates data and metadata for a respcontrol packet - * Returns data size. - */ -ssize_t EncodeGetparam( - struct metadata * m, /* data_len and msg_type will be populated*/ - uint8_t * data, /* Output buffer */ - size_t data_size, /* Max buffer size */ - const struct controller_message * cm) /* Message to encode */ -{ - m->msg_type = GETPARAM_ID; - m->data_len = GP_DATA_SIZE; - - if (data_size < GP_DATA_SIZE) { - return -1; - } - - data[CTRL_ID] = cm->id; - data[CTRLVAL_ID] = cm->value_id; - - return GP_DATA_SIZE; -} - -/* Decode a metadata and data to populate a controller. - * Returns 0 on success, -1 on failure. - */ -int DecodeGetparam( - struct controller_message * cm, /* Decoded controller message */ - const struct metadata * m, /* Metadata to aid in decoding */ - const uint8_t * data) /* Data to decode */ -{ - if (m->data_len < GP_DATA_SIZE) { - return -1; - } - if (m->msg_type != GETPARAM_ID) { - return -1; - } - - cm->id = data[CTRL_ID]; - cm->value_id = data[CTRLVAL_ID]; - - return 0; -} diff --git a/groundStation/src/backend/old_main.cold b/groundStation/src/backend/old_main.cold deleted file mode 100644 index 5234bcc567a6e574b30eea671b3f977a7211f478..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/old_main.cold +++ /dev/null @@ -1,73 +0,0 @@ -#include <libcli.h> -#include <stdlib.h> -#include <sys/types.h> -#include <sys/socket.h> -#include <string.h> -#include <strings.h> -#include <signal.h> -#include <unistd.h> -#include <arpa/inet.h> - - -#define CLITEST_PORT 8000 - -int fn_help(struct cli_def *cli, const char *command, char *argv[], int argc); - -struct cli_def * cli; -int on = 1; - -int main(int argc, char **argv) -{ - int s, x; - struct sockaddr_in addr; - - if ((s = socket(AF_INET, SOCK_STREAM, 0)) < 0) - { - perror("socket"); - return 1; - } - setsockopt(s, SOL_SOCKET, SO_REUSEADDR, &on, sizeof(on)); - - memset(&addr, 0, sizeof(addr)); - addr.sin_family = AF_INET; - addr.sin_addr.s_addr = htonl(INADDR_ANY); - addr.sin_port = htons(CLITEST_PORT); - - if (bind(s, (struct sockaddr *) &addr, sizeof(addr)) < 0) - { - perror("bind"); - return 1; - } - - if (listen(s, 50) < 0) - { - perror("listen"); - return 1; - } - - printf("Listening on port %d\n", CLITEST_PORT); - - cli = cli_init(); - cli_set_banner(cli, "Welcome to my test cli"); - - cli_register_command(cli, NULL, "helpme", fn_help, PRIVILEGE_UNPRIVILEGED, MODE_EXEC, "displays help info for a command"); - - - - - while((x = accept(s, NULL, NULL))) - { - cli_loop(cli, x); - close(x); - } - - - cli_done(cli); -} - - -int fn_help(struct cli_def *cli, const char *command, char *argv[], int argc) { - printf("you ran the help function!!\n"); - return 0; -} - diff --git a/groundStation/src/backend/output.c b/groundStation/src/backend/output.c new file mode 100644 index 0000000000000000000000000000000000000000..0c3195c95b76158e657fd05f8028502bd18f5cdd --- /dev/null +++ b/groundStation/src/backend/output.c @@ -0,0 +1,77 @@ +#include <sys/types.h> + +#include "output.h" +#include "../../../common/commands.h" +#include "bitwise.h" + + +enum GetoutputData { + GO_BLOCK_ID_L, + GO_BLOCK_ID_H, + GO_OUTPUT_ID_L, + GO_OUTPUT_ID_H, + GO_DATA_SIZE +}; + +/* Creates data and metadata for a setcontrol packet + * Returns data size. + */ +ssize_t EncodeGetOutput( + struct metadata * m, /* data_len and msg_type will be populated*/ + uint8_t * data, /* Output buffer */ + size_t data_size, /* Max buffer size */ + const char * msg) /* Message to encode */ +{ + m->msg_type = GETOUTPUT_ID; + m->data_len = GO_DATA_SIZE; + + if (data_size < GO_DATA_SIZE) { + return -1; + } + + uint16_t block, output; + + sscanf(msg, "getoutput %hu %hu", &block, &output); + + data[GO_BLOCK_ID_L] = LSByte16(block); + data[GO_BLOCK_ID_H] = MSByte16(block); + data[GO_OUTPUT_ID_L] = LSByte16(output); + data[GO_OUTPUT_ID_H] = MSByte16(output); + + return GO_DATA_SIZE; +} + +enum ResponseData { + RESP_BLOCK_ID_L, + RESP_BLOCK_ID_H, + RESP_OUTPUT_ID_L, + RESP_OUTPUT_ID_H, + RESP_VAL_1, + RESP_VAL_2, + RESP_VAL_3, + RESP_VAL_4, + RESP_DATA_SIZE +}; + +/* Decode a metadata and data to populate a controller. + * Returns bytes written to msg, -1 on failure. + */ +int DecodeResponseOutput( + char * msg, /* Decoded controller message */ + const struct metadata * m, /* Metadata to aid in decoding */ + const uint8_t * data) /* Data to decode */ +{ + if (m->data_len < RESP_DATA_SIZE) { + return -1; + } + if (m->msg_type != RESPOUTPUT_ID) { + return -1; + } + + return sprintf(msg, "getoutput %hu %hu %f\n", + BytesTo16(data[RESP_BLOCK_ID_L], data[RESP_BLOCK_ID_H]), + BytesTo16(data[RESP_OUTPUT_ID_L], data[RESP_OUTPUT_ID_H]), + BytesToFloat(data[RESP_VAL_1], data[RESP_VAL_2], + data[RESP_VAL_3], data[RESP_VAL_4])); +} + diff --git a/groundStation/src/backend/getparam.h b/groundStation/src/backend/output.h similarity index 50% rename from groundStation/src/backend/getparam.h rename to groundStation/src/backend/output.h index c9d9096df464aae6e802e68f9a84236f99009c16..034d6ec156d25fb27c481d08cfce1c66d7fc7f26 100644 --- a/groundStation/src/backend/getparam.h +++ b/groundStation/src/backend/output.h @@ -1,8 +1,7 @@ -#ifndef _getparam_h -#define _getparam_h +#ifndef _getoutput_h +#define _getoutput_h #include "packet.h" -#include "controller.h" #include <sys/types.h> @@ -10,17 +9,18 @@ /* Creates data and metadata for a getcontrol packet. * Returns data size. */ -ssize_t EncodeGetparam( +ssize_t EncodeGetOutput( struct metadata *m, /* Out */ uint8_t *data, /* Out */ size_t data_size, /* Data buffer max size */ - const struct controller_message *cm); /* Value is not used; only IDs */ + const char * msg); /* Value is not used; only IDs */ -/* Decode a metadata and data to populate a message - * Returns 0 on success, -1 on failure + +/* Decode a metadata and data to populate a controller. + * Returns bytes written to msg, -1 on failure. */ -int DecodeGetparam( - struct controller_message *cm, /* Out. Value is undefined */ +int DecodeResponseOutput( + char * msg, /* Out */ const struct metadata *m, /* In */ const uint8_t * data); /* In */ diff --git a/groundStation/src/backend/param.c b/groundStation/src/backend/param.c new file mode 100644 index 0000000000000000000000000000000000000000..749960fe429f372d77f9a25c2e24029689898414 --- /dev/null +++ b/groundStation/src/backend/param.c @@ -0,0 +1,126 @@ +#include <sys/types.h> + +#include "param.h" +#include "../../../common/commands.h" +#include "bitwise.h" + +enum GetparamData { + GP_BLOCK_ID_L, + GP_BLOCK_ID_H, + GP_PARAM_ID_L, + GP_PARAM_ID_H, + GP_DATA_SIZE +}; + +/* Creates data and metadata for a respcontrol packet + * Returns data size. + */ +ssize_t EncodeGetParam( + struct metadata * m, /* data_len and msg_type will be populated*/ + uint8_t * data, /* Output buffer */ + size_t data_size, /* Max buffer size */ + const char * msg) /* Message to encode */ +{ + m->msg_type = GETPARAM_ID; + m->data_len = GP_DATA_SIZE; + + if (data_size < GP_DATA_SIZE) { + return -1; + } + + uint16_t block, param; + sscanf(msg, "getparam %hu %hu", &block, ¶m); + + + data[GP_BLOCK_ID_L] = LSByte16(block); + data[GP_BLOCK_ID_H] = MSByte16(block); + + data[GP_PARAM_ID_L] = LSByte16(param); + data[GP_PARAM_ID_H] = MSByte16(param); + + return GP_DATA_SIZE; +} + +enum SetparamData { + SP_BLOCK_ID_L, + SP_BLOCK_ID_H, + SP_PARAM_ID_L, + SP_PARAM_ID_H, + SP_VAL_1, + SP_VAL_2, + SP_VAL_3, + SP_VAL_4, + SP_DATA_SIZE +}; + +/* Creates data and metadata for a setcontrol packet + * Returns data size. + */ +ssize_t EncodeSetParam( + struct metadata * m, /* data_len and msg_type will be populated*/ + uint8_t * data, /* Output buffer */ + size_t data_size, /* Max buffer size */ + const char * msg) /* Message to encode */ +{ + m->msg_type = SETPARAM_ID; + m->data_len = SP_DATA_SIZE; + + if (data_size < SP_DATA_SIZE) { + return -1; + } + + uint16_t block, param; + float val; + + sscanf(msg, "setparam %hu %hu %f", &block, ¶m, &val); + + data[SP_BLOCK_ID_L] = LSByte16(block); + data[SP_BLOCK_ID_H] = MSByte16(block); + + data[SP_PARAM_ID_L] = LSByte16(param); + data[SP_PARAM_ID_H] = MSByte16(param); + + + data[SP_VAL_1] = FloatByte1(val); + data[SP_VAL_2] = FloatByte2(val); + data[SP_VAL_3] = FloatByte3(val); + data[SP_VAL_4] = FloatByte4(val); + + return SP_DATA_SIZE; +} + + + +enum ResponseData { + RESP_BLOCK_ID_L, + RESP_BLOCK_ID_H, + RESP_PARAM_ID_L, + RESP_PARAM_ID_H, + RESP_VAL_1, + RESP_VAL_2, + RESP_VAL_3, + RESP_VAL_4, + RESP_DATA_SIZE +}; + +/* Decode a metadata and data to populate a controller. + * Returns bytes written to msg, -1 on failure. + */ +int DecodeResponseParam( + char * msg, /* Decoded controller message */ + const struct metadata * m, /* Metadata to aid in decoding */ + const uint8_t * data) /* Data to decode */ +{ + if (m->data_len < RESP_DATA_SIZE) { + return -1; + } + if (m->msg_type != RESPPARAM_ID) { + return -1; + } + + return sprintf(msg, "getparam %hu %hu %f\n", + BytesTo16(data[RESP_BLOCK_ID_L], data[RESP_BLOCK_ID_H]), + BytesTo16(data[RESP_PARAM_ID_L], data[RESP_PARAM_ID_H]), + BytesToFloat(data[RESP_VAL_1], data[RESP_VAL_2], + data[RESP_VAL_3], data[RESP_VAL_4])); +} diff --git a/groundStation/src/backend/param.h b/groundStation/src/backend/param.h new file mode 100644 index 0000000000000000000000000000000000000000..96ecc633290abaea67d5083be4ef8b013901af07 --- /dev/null +++ b/groundStation/src/backend/param.h @@ -0,0 +1,36 @@ +#ifndef _param_h +#define _param_h + +#include "packet.h" + +#include <sys/types.h> + + +/* Creates data and metadata for a getcontrol packet. + * Returns data size. + */ +ssize_t EncodeGetParam( + struct metadata *m, /* Out */ + uint8_t *data, /* Out */ + size_t data_size, /* Data buffer max size */ + const char * msg); /* Value is not used; only IDs */ + +/* Creates data and metadata for a setcontrol packet + * Returns data size. + */ +ssize_t EncodeSetParam( + struct metadata * m, /* data_len and msg_type will be populated*/ + uint8_t * data, /* Output buffer */ + size_t data_size, /* Max buffer size */ + const char * msg); /* Message to encode */ + +/* Decode a metadata and data to populate a controller. + * Returns bytes written to msg, -1 on failure. + */ +int DecodeResponseParam( + char * msg, /* Out */ + const struct metadata *m, /* In */ + const uint8_t * data); /* In */ + + +#endif diff --git a/groundStation/src/backend/responseparam.c b/groundStation/src/backend/responseparam.c deleted file mode 100644 index f6a8d44b268493b0501759327334ed58e5cb0685..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/responseparam.c +++ /dev/null @@ -1,64 +0,0 @@ -#include "responseparam.h" -#include "commands.h" -#include "bitwise.h" - -#include <sys/types.h> - -enum ResponseData { - CTRL_ID, - CTRLVAL_ID, - VAL_1, - VAL_2, - VAL_3, - VAL_4, - RESP_DATA_SIZE -}; - -/* Creates data and metadata for a respcontrol packet - * Returns data size. - */ -ssize_t EncodeResponseParam( - struct metadata * m, /* data_len and msg_type will be populated*/ - uint8_t * data, /* Output buffer */ - size_t data_size, /* Max buffer size */ - const struct controller_message * cm) /* Message to encode */ -{ - m->msg_type = RESPPARAM_ID; - m->data_len = RESP_DATA_SIZE; - - if (data_size < RESP_DATA_SIZE) { - return -1; - } - - data[CTRL_ID] = cm->id; - data[CTRLVAL_ID] = cm->value_id; - data[VAL_1] = FloatByte1(cm->value); - data[VAL_2] = FloatByte2(cm->value); - data[VAL_3] = FloatByte3(cm->value); - data[VAL_4] = FloatByte4(cm->value); - - return RESP_DATA_SIZE; -} - -/* Decode a metadata and data to populate a controller. - * Returns 0 on success, -1 on failure. - */ -int DecodeResponseParam( - struct controller_message * cm, /* Decoded controller message */ - const struct metadata * m, /* Metadata to aid in decoding */ - const uint8_t * data) /* Data to decode */ -{ - if (m->data_len < RESP_DATA_SIZE) { - return -1; - } - if (m->msg_type != RESPPARAM_ID) { - return -1; - } - - cm->id = data[CTRL_ID]; - cm->value_id = data[CTRLVAL_ID]; - cm->value = BytesToFloat(data[VAL_1], data[VAL_2], - data[VAL_3], data[VAL_4]); - - return 0; -} diff --git a/groundStation/src/backend/responseparam.h b/groundStation/src/backend/responseparam.h deleted file mode 100644 index 5e3224477b46d8384e6f10b30f07e5571d089cfa..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/responseparam.h +++ /dev/null @@ -1,28 +0,0 @@ -#ifndef _responseparam_h -#define _responseparam_h - -#include "packet.h" -#include "controller.h" - -#include <sys/types.h> - - -/* Creates data and metadata for a respcontrol packet. - * Returns data size. - */ -ssize_t EncodeResponseParam( - struct metadata *m, /* Out */ - uint8_t *data, /* Out */ - size_t data_size, /* Data buffer max size */ - const struct controller_message *cm); /* In */ - -/* Decode a metadata and data to populate a message - * Returns 0 on success, -1 on failure - */ -int DecodeResponseParam( - struct controller_message *cm, /* Out */ - const struct metadata *m, /* In */ - const uint8_t * data); /* In */ - - -#endif diff --git a/groundStation/src/backend/setparam.c b/groundStation/src/backend/setparam.c deleted file mode 100644 index c97ed01f4d16d92ae18434d3dbf5d8da9c11b94a..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/setparam.c +++ /dev/null @@ -1,65 +0,0 @@ -#include "setparam.h" -#include "commands.h" -#include "bitwise.h" - -#include <sys/types.h> - -enum SetparamData { - CTRL_ID, - CTRLVAL_ID, - VAL_1, - VAL_2, - VAL_3, - VAL_4, - SP_DATA_SIZE -}; - -/* Creates data and metadata for a setcontrol packet - * Returns data size. - */ -ssize_t EncodeSetparam( - struct metadata * m, /* data_len and msg_type will be populated*/ - uint8_t * data, /* Output buffer */ - size_t data_size, /* Max buffer size */ - const struct controller_message * cm) /* Message to encode */ -{ - m->msg_type = SETPARAM_ID; - m->data_len = SP_DATA_SIZE; - - if (data_size < SP_DATA_SIZE) { - return -1; - } - - data[CTRL_ID] = cm->id; - data[CTRLVAL_ID] = cm->value_id; - data[VAL_1] = FloatByte1(cm->value); - data[VAL_2] = FloatByte2(cm->value); - data[VAL_3] = FloatByte3(cm->value); - data[VAL_4] = FloatByte4(cm->value); - - return SP_DATA_SIZE; -} - -/* Decode a metadata and data to populate a controller. - * Returns 0 on success, -1 on failure. - */ -int DecodeSetparam( - struct controller_message * cm, /* Decoded controller message */ - const struct metadata * m, /* Metadata to aid in decoding */ - const uint8_t * data) /* Data to decode */ -{ - if (m->data_len < SP_DATA_SIZE) { - return -1; - } - if (m->msg_type != SETPARAM_ID) { - return -1; - } - - - cm->id = data[CTRL_ID]; - cm->value_id = data[CTRLVAL_ID]; - cm->value = BytesToFloat(data[VAL_1], data[VAL_2], - data[VAL_3], data[VAL_4]); - - return 0; -} diff --git a/groundStation/src/backend/setparam.h b/groundStation/src/backend/setparam.h deleted file mode 100644 index 671d7aa240ef43c6bb82fc8eaa1b29826b70c36c..0000000000000000000000000000000000000000 --- a/groundStation/src/backend/setparam.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef _setparam_h -#define _setparam_h - -#include "packet.h" -#include "controller.h" - -#include <sys/types.h> - -/* Creates data and metadata for a setcontrol packet - * Returns data size. - */ -ssize_t EncodeSetparam( - struct metadata * m, /* data_len and msg_type will be populated*/ - uint8_t * data, /* Output buffer */ - size_t data_size, /* Max buffer size */ - const struct controller_message * cm); /* Message to encode */ - -/* Decode a metadata and data to populate a controller. - * Returns 0 on success, -1 on failure. - */ -int DecodeSetparam( - struct controller_message * cm, /* Decoded controller message */ - const struct metadata * m, /* Metadata to aid in decoding */ - const uint8_t * data); /* Data to decode */ - - -#endif diff --git a/groundStation/src/backend/source.c b/groundStation/src/backend/source.c new file mode 100644 index 0000000000000000000000000000000000000000..dac52612d810c500644c8a5286595e090046d631 --- /dev/null +++ b/groundStation/src/backend/source.c @@ -0,0 +1,114 @@ +#include <sys/types.h> + +#include "source.h" +#include "../../../common/commands.h" +#include "bitwise.h" + + +enum GetsourceData { + GS_BLOCK_ID_L, + GS_BLOCK_ID_H, + GS_INPUT_ID_L, + GS_INPUT_ID_H, + GS_DATA_SIZE +}; + +/* Creates data and metadata for a setcontrol packet + * Returns data size. + */ +ssize_t EncodeGetSource( + struct metadata * m, /* data_len and msg_type will be populated*/ + uint8_t * data, /* Output buffer */ + size_t data_size, /* Max buffer size */ + const char * msg) /* Message to encode */ +{ + m->msg_type = GETSOURCE_ID; + m->data_len = GS_DATA_SIZE; + + if (data_size < GS_DATA_SIZE) { + return -1; + } + uint16_t block, input; + + sscanf(msg, "getsource %hu %hu", &block, &input); + + data[GS_BLOCK_ID_L] = LSByte16(block); + data[GS_BLOCK_ID_H] = MSByte16(block); + data[GS_INPUT_ID_L] = LSByte16(input); + data[GS_INPUT_ID_H] = MSByte16(input); + + return GS_DATA_SIZE; +} + +enum SetsourceData { + SS_DST_BLOCK_ID_L, + SS_DST_BLOCK_ID_H, + SS_DST_INPUT_ID_L, + SS_DST_INPUT_ID_H, + SS_SRC_BLOCK_ID_L, + SS_SRC_BLOCK_ID_H, + SS_SRC_OUTPUT_ID_L, + SS_SRC_OUTPUT_ID_H, + SS_DATA_SIZE +}; + +/* Creates data and metadata for a setcontrol packet + * Returns data size. + */ +ssize_t EncodeSetSource( + struct metadata * m, /* data_len and msg_type will be populated*/ + uint8_t * data, /* Output buffer */ + size_t data_size, /* Max buffer size */ + const char * msg) /* Message to encode */ +{ + m->msg_type = SETSOURCE_ID; + m->data_len = SS_DATA_SIZE; + + if (data_size < SS_DATA_SIZE) { + return -1; + } + + uint16_t dst_block, dst_input; + uint16_t src_block, src_output; + + sscanf(msg, "setsource %hu %hu %hu %hu", &dst_block, &dst_input, &src_block, &src_output); + + data[SS_DST_BLOCK_ID_L] = LSByte16(dst_block); + data[SS_DST_BLOCK_ID_H] = MSByte16(dst_block); + data[SS_DST_INPUT_ID_L] = LSByte16(dst_input); + data[SS_DST_INPUT_ID_H] = MSByte16(dst_input); + + data[SS_SRC_BLOCK_ID_L] = LSByte16(src_block); + data[SS_SRC_BLOCK_ID_H] = MSByte16(src_block); + data[SS_SRC_OUTPUT_ID_L] = LSByte16(src_output); + data[SS_SRC_OUTPUT_ID_H] = MSByte16(src_output); + + return SS_DATA_SIZE; +} + + +enum ResponseData { + RESP_DST_BLOCK_ID, + RESP_DST_INPUT_ID, + RESP_SRC_BLOCK_ID, + RESP_SRC_OUTPUT_ID, + RESP_DATA_SIZE +}; + +/* Decode a metadata and data to populate a controller. + * Returns bytes written to msg, -1 on failure. + */ +int DecodeResponseSource( + char * msg, /* Decoded controller message */ + const struct metadata * m, /* Metadata to aid in decoding */ + const uint8_t * data) /* Data to decode */ +{ + if (m->data_len < RESP_DATA_SIZE) { + return -1; + } + if (m->msg_type != RESPSOURCE_ID) { + return -1; + } + + return sprintf(msg, "getsource %d %d\n", data[RESP_SRC_BLOCK_ID], data[RESP_SRC_OUTPUT_ID]); +} diff --git a/groundStation/src/backend/source.h b/groundStation/src/backend/source.h new file mode 100644 index 0000000000000000000000000000000000000000..577f27717b9fbce4504169bdb6e163a528cc7c34 --- /dev/null +++ b/groundStation/src/backend/source.h @@ -0,0 +1,35 @@ +#ifndef _source_h +#define _source_h + +#include "packet.h" + +#include <sys/types.h> + + +/* Creates data and metadata for a getcontrol packet. + * Returns data size. + */ +ssize_t EncodeGetSource( + struct metadata *m, /* Out */ + uint8_t *data, /* Out */ + size_t data_size, /* Data buffer max size */ + const char * msg); /* Value is not used; only IDs */ + +/* Creates data and metadata for a setcontrol packet + * Returns data size. + */ +ssize_t EncodeSetSource( + struct metadata * m, /* data_len and msg_type will be populated*/ + uint8_t * data, /* Output buffer */ + size_t data_size, /* Max buffer size */ + const char * msg); /* Message to encode */ + +/* Decode a metadata and data to populate a controller. + * Returns bytes written to msg, -1 on failure. + */ +int DecodeResponseSource( + char * msg, /* Out */ + const struct metadata *m, /* In */ + const uint8_t * data); /* In */ + +#endif diff --git a/groundStation/src/backend/update.c b/groundStation/src/backend/update.c index db546e05a3891ff0f9f52bc2ecdfc658012ed65b..1f51f0be78c78b4671f2066124e15c90b96d3621 100644 --- a/groundStation/src/backend/update.c +++ b/groundStation/src/backend/update.c @@ -1,5 +1,5 @@ #include "update.h" -#include "commands.h" +#include "../../../common/commands.h" #include "bitwise.h" #include <sys/types.h> diff --git a/groundStation/src/cli/cli.h b/groundStation/src/cli/cli.h index e82bd5cda7e1d31d2aa31dffee2ac30a2fa372f1..707d16836783fe34279d1b0935995fa535a67fad 100644 --- a/groundStation/src/cli/cli.h +++ b/groundStation/src/cli/cli.h @@ -1,40 +1,38 @@ #ifndef __CLI_H #define __CLI_H -#include "cli_setsetpoint.h" -#include "cli_getsetpoint.h" #include "cli_monitor.h" -#include "cli_setpid.h" -#include "cli_getpid.h" -#include "cli_getimu.h" +#include "cli_source.h" +#include "cli_param.h" +#include "cli_output.h" enum CommandNameIds{ CMD_MONITOR, - CMD_GETPID, - CMD_SETPID, - CMD_GETIMU, - CMD_SETSETPOINT, - CMD_GETSETPOINT, + CMD_GETSOURCE, + CMD_SETSOURCE, + CMD_GETPARAM, + CMD_SETPARAM, + CMD_GETOUTPUT, MAX_COMMANDS }; typedef int (*cli_function_ptr)(struct backend_conn *, int, char **); static cli_function_ptr cli_functions[] = { &cli_monitor, - &cli_getpid, - &cli_setpid, - &cli_getimu, - &cli_setsetpoint, - &cli_getsetpoint + &cli_getsource, + &cli_setsource, + &cli_getparam, + &cli_setparam, + &cli_getoutput, }; static char* commandNames[MAX_COMMANDS] = { "monitor", - "getpid", - "setpid", - "getimu", - "setsetpoint", - "getsetpoint" + "getsource", + "setsource", + "getparam", + "setparam", + "getoutput" }; #endif /* __CLI_H */ \ No newline at end of file diff --git a/groundStation/src/cli/cli_getimu.c b/groundStation/src/cli/cli_getimu.c deleted file mode 100644 index 5825140af8c0d7e224b045c533d02ed61134a5f2..0000000000000000000000000000000000000000 --- a/groundStation/src/cli/cli_getimu.c +++ /dev/null @@ -1,8 +0,0 @@ -#include <stdio.h> - -#include "cli_getimu.h" - -int cli_getimu(struct backend_conn * conn, int argc, char ** argv) { - printf("This functionality has not been added yet\n"); - return 0; -} diff --git a/groundStation/src/cli/cli_getimu.h b/groundStation/src/cli/cli_getimu.h deleted file mode 100644 index 2535f1ae87dfba4cb616adb0aa72e686c2cd4fe7..0000000000000000000000000000000000000000 --- a/groundStation/src/cli/cli_getimu.h +++ /dev/null @@ -1,8 +0,0 @@ -#ifndef __CLI_GETIMU_H -#define __CLI_GETIMU_H - -#include "frontend_getimu.h" - -int cli_getimu(struct backend_conn * conn, int argc, char ** argv); - -#endif /* __CLI_GETIMU_H */ \ No newline at end of file diff --git a/quad/.gitignore b/quad/.gitignore index 53a35d022ad1dea8f70ea943700a97f57e643399..43d04fb118c3ab8c1ea06f84c8a8b11598990756 100644 --- a/quad/.gitignore +++ b/quad/.gitignore @@ -1,3 +1,7 @@ -zybo_fsbl_bsp/ -zybo_fsbl/ test.log +inc/ +obj/ +lib/ +lib-zybo/ +TAGS +out/ diff --git a/quad/Makefile b/quad/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..f784e354f4310db4d4c9241d11b731c65cba1249 --- /dev/null +++ b/quad/Makefile @@ -0,0 +1,43 @@ +INCDIR = inc +LIBDIR = lib +OUTDIR = out +WS = $(CURDIR)/xsdk_workspace + +BOOT = $(OUTDIR)/BOOT.bin + +.PHONY: all libs zybo boot test clean deep-clean + +all: libs + +libs: + $(MAKE) -C src/test + $(MAKE) -C src/queue + $(MAKE) -C src/computation_graph + $(MAKE) -C src/quad_app + +zybo: + bash scripts/build_zybo.sh + +boot: $(BOOT) + +test: + $(MAKE) -C src/queue test + $(MAKE) -C src/computation_graph test + $(MAKE) -C src/quad_app test + +clean: + rm -rf $(INCDIR) $(LIBDIR) $(OUTDIR) + +deep-clean: + make clean + $(MAKE) -C src/test clean + $(MAKE) -C src/queue clean + $(MAKE) -C src/computation_graph 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 diff --git a/quad/README.md b/quad/README.md new file mode 100644 index 0000000000000000000000000000000000000000..8f857b03bcd9bba8e4e76f3617313d0ad7dd2b2d --- /dev/null +++ b/quad/README.md @@ -0,0 +1,66 @@ +# Quadcopter + +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 +``` + +The main XSDK project that actually runs on the Zybo is located at: +``` +xsdk_workspace/modular_quad_pid/main.c +``` + +## Building + +### Libraries + +To build the libraries: +``` +make libs +``` + +You can also build each library individually inside their respective project +directories: +``` +cd src/<project> && make +``` + +### XSDK Project + +To build the XSDK project that runs on the Zybo (only works on co3050): +``` +make zybo +``` + +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 + +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. +``` +make test +``` + +You can also run the test for specific library inside its respective project +directory: +``` +cd src/<project> && make test +``` + +### XSDK Project + +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. diff --git a/quad/ci-build.sh b/quad/ci-build.sh deleted file mode 100644 index 36ff958b187383adb5a1007f85e6bffa1f5b09d2..0000000000000000000000000000000000000000 --- a/quad/ci-build.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/bash - -QUAD_ROOT=$PROJECT_ROOT/quad -export QUAD_ROOT - -# Build Quad code -cd $QUAD_ROOT/sw/modular_quad_pid/ -bash build.sh || exit 1 diff --git a/quad/ci-test.sh b/quad/ci-test.sh deleted file mode 100644 index b1e40c7ef4c6424ba48aec4745aab5317ff982fa..0000000000000000000000000000000000000000 --- a/quad/ci-test.sh +++ /dev/null @@ -1,17 +0,0 @@ -#!/bin/bash - -QUAD_ROOT=$PROJECT_ROOT/quad -export QUAD_ROOT - -# Build Test Library -cd $QUAD_ROOT/lib/test -make || exit 1 - -# Test UART buffer -cd $QUAD_ROOT/sw/modular_quad_pid/test -make || exit 1 -./test_uart_buff || exit 1 - -cd $QUAD_ROOT/computation_graph/test -make || exit 1 -./test_computation_graph || exit 1 diff --git a/quad/computation_graph/.gitignore b/quad/computation_graph/.gitignore deleted file mode 100644 index 429b549db1ac8959e01fbdaf54012317473f58ee..0000000000000000000000000000000000000000 --- a/quad/computation_graph/.gitignore +++ /dev/null @@ -1,4 +0,0 @@ -bin/ -build/ -computation_graph -test/test_computation_graph diff --git a/quad/computation_graph/src/main.c b/quad/computation_graph/src/main.c deleted file mode 100644 index b7fb2d3302228793a67465812e155e37e2f3b1f8..0000000000000000000000000000000000000000 --- a/quad/computation_graph/src/main.c +++ /dev/null @@ -1,42 +0,0 @@ -#include <stdio.h> -#include "computation_graph.h" -#include "graph_blocks/node_add.h" -#include "graph_blocks/node_mult.h" -#include "graph_blocks/node_constant.h" -#include "graph_blocks/node_gain.h" -#include "tests.h" - -int main() { -// struct computation_graph *graph = create_graph(); -// -// int const1 = graph_add_node_const(graph, "Const 2"); -// graph_set_param_val(graph, const1, CONST_SET, 2); -// int const2 = graph_add_node_const(graph, "Const 1"); -// graph_set_param_val(graph, const2, CONST_SET, 3); -// -// int add1_id = graph_add_node_add(graph, "Add"); -// graph_set_source(graph, add1_id, ADD_SUMMAND1, const1, CONST_VAL); -// graph_set_source(graph, add1_id, ADD_SUMMAND2, const2, CONST_VAL); -// -// int gain1_id = graph_add_node_gain(graph, "Gain"); -// graph_set_param_val(graph, gain1_id, GAIN_GAIN, 3); -// graph_set_source(graph, gain1_id, GAIN_INPUT, add1_id, ADD_SUM); -// -// int mult1_id = graph_add_node_mult(graph, "Mult"); -// graph_set_source(graph, mult1_id, MULT_MULTIPLICAND2, gain1_id, GAIN_RESULT); -// graph_set_source(graph, mult1_id, MULT_MULTIPLICAND1, const1, CONST_VAL); -// -// graph_compute_node(graph, mult1_id); - -// FILE* dot_fp; -// dot_fp = fopen("..\\comp_graph.dot", "w"); -// export_dot(graph, dot_fp); -// fclose(dot_fp); -// printf("Sum is %f\n", graph_get_output(graph, mult1_id, GAIN_RESULT)); - - int success = graph_run_tests(); - printf("Success: %s\n", success == 0 ? "Yes" : "No"); - fflush(stdout); - - return 0; -} diff --git a/quad/computation_graph/src/tests.c b/quad/computation_graph/src/tests.c deleted file mode 100644 index 2f120a2693f4b2ee8116d192b4494299f93f44a8..0000000000000000000000000000000000000000 --- a/quad/computation_graph/src/tests.c +++ /dev/null @@ -1,151 +0,0 @@ -// -// Created by dawehr on 2/9/2017. -// - -#include "tests.h" -#define GRAPH_TEST_EPS 0.00001 - -static int nequal(double val1, double val2) { - if (fabs(val1 - val2) < GRAPH_TEST_EPS) { - return 0; - } - return -1; -} - -int graph_run_tests() { - int success = 0; - success |= graph_test_one_add(); - success |= graph_test_circular_runs(); - success |= graph_test_circular_resets(); - success |= graph_test_accumulator(); - success |= graph_test_single_run(); - success |= graph_test_reset_rules(); - success |= graph_test_self_loop(); - return success; -} - -int graph_test_one_add() { - struct computation_graph *graph = create_graph(); - int block = graph_add_node_add(graph, "Add"); - int cblock3 = graph_add_node_const(graph, "3"); - graph_set_param_val(graph, cblock3, CONST_SET, 3); - int cblock4 = graph_add_node_const(graph, "4"); - graph_set_param_val(graph, cblock4, CONST_SET, 4); - graph_set_source(graph, block, ADD_SUMMAND1, cblock3, CONST_VAL); - graph_set_source(graph, block, ADD_SUMMAND2, cblock4, CONST_VAL); - int to_compute_for[1] = {block}; - graph_compute_nodes(graph, to_compute_for, 1); - double result = graph_get_output(graph, block, ADD_SUM); - return nequal(result, 7); -} - - -int graph_test_circular_runs() { - struct computation_graph *graph = create_graph(); - int gain1 = graph_add_node_gain(graph, "gain1"); - int gain2 = graph_add_node_gain(graph, "gain2"); - graph_set_source(graph, gain2, GAIN_INPUT, gain1, GAIN_RESULT); - graph_set_source(graph, gain1, GAIN_INPUT, gain2, GAIN_RESULT); - int to_compute_for[1] = {gain2}; - graph_compute_nodes(graph, to_compute_for, 1); - // If no infinite loop, then success. Value is undefined for circular graphs - return 0; -} - -int graph_test_circular_resets() { - struct computation_graph *graph = create_graph(); - int acum1 = graph_add_node_accum(graph, "accumulator1"); - int acum2 = graph_add_node_accum(graph, "accumulator2"); - graph_set_source(graph, acum2, ACCUM_IN, acum1, ACCUMULATED); - graph_set_source(graph, acum1, ACCUM_IN, acum2, ACCUMULATED); - return 0; // Passes if no infinite loop -} - -// Tests the accumulator block, thereby testing reset and state changes -int graph_test_accumulator() { - struct computation_graph *graph = create_graph(); - int cblock = graph_add_node_const(graph, "const"); - int acum_b = graph_add_node_accum(graph, "accumulator"); - graph_set_source(graph, acum_b, ACCUM_IN, cblock, CONST_VAL); - - int to_compute_for[1] = {acum_b}; - graph_set_param_val(graph, cblock, CONST_SET, 3); - graph_compute_nodes(graph, to_compute_for, 1); - graph_set_param_val(graph, cblock, CONST_SET, 8); - graph_compute_nodes(graph, to_compute_for, 1); - graph_set_param_val(graph, cblock, CONST_SET, -2); - graph_compute_nodes(graph, to_compute_for, 1); - - double result = graph_get_output(graph, acum_b, ACCUMULATED); - if (nequal(result, 9)) { - printf("graph_test_accumulator failed on step 1, equals %f\n", result); - return -1; - } - - // Test reset on source set - int gain_b = graph_add_node_gain(graph, "Gain"); - graph_set_param_val(graph, gain_b, GAIN_GAIN, 1); - graph_set_source(graph, gain_b, GAIN_INPUT, acum_b, ACCUMULATED); - to_compute_for[0] = gain_b; - graph_compute_nodes(graph, to_compute_for, 1); - result = graph_get_output(graph, gain_b, GAIN_RESULT); - if (nequal(result, -2)) { - printf("graph_test_accumulator failed on step 2\n"); - return -2; - } - return 0; -} - -// Tests that a block will only execute once per compute, -// even if its output is connected to multiple inputs -int graph_test_single_run() { - struct computation_graph *graph = create_graph(); - int acum_b = graph_add_node_accum(graph, "accumulator"); - int add_block = graph_add_node_add(graph, "Add"); - int cblock = graph_add_node_const(graph, "const"); - graph_set_param_val(graph, cblock, CONST_SET, 2); - - - graph_set_source(graph, acum_b, ACCUM_IN, cblock, CONST_VAL); - graph_set_source(graph, add_block, ADD_SUMMAND1, acum_b, ACCUMULATED); - graph_set_source(graph, add_block, ADD_SUMMAND2, acum_b, ACCUMULATED); - - int to_compute_for[1] = {add_block}; - graph_compute_nodes(graph, to_compute_for, 1); - double result = graph_get_output(graph, add_block, ADD_SUM); - return nequal(result, 4); -} - -// Tests that upon connection of a second child, a block will not reset -int graph_test_reset_rules() { - struct computation_graph *graph = create_graph(); - int cblock = graph_add_node_const(graph, "5"); - graph_set_param_val(graph, cblock, CONST_SET, 5); - int acum_b = graph_add_node_accum(graph, "accumulator"); - int gain1 = graph_add_node_gain(graph, "gain1"); - graph_set_param_val(graph, gain1, GAIN_GAIN, 1); - - graph_set_source(graph, gain1, GAIN_INPUT, acum_b, ACCUMULATED); - graph_set_source(graph, acum_b, ACCUM_IN, cblock, CONST_VAL); - int to_compute_for[1] = {gain1}; - graph_compute_nodes(graph, to_compute_for, 1); - // state of acum_b is now 5 - - int gain2 = graph_add_node_gain(graph, "gain2"); - graph_set_param_val(graph, gain2, GAIN_GAIN, 1); - // Connect gain 2, and accumulator should not get reset - graph_set_source(graph, gain2, GAIN_INPUT, acum_b, ACCUMULATED); - to_compute_for[0] = gain2; - graph_compute_nodes(graph, to_compute_for, 1); - double result = graph_get_output(graph, gain2, GAIN_RESULT); - return nequal(result, 10); -} - -int graph_test_self_loop() { - struct computation_graph *graph = create_graph(); - int gain1 = graph_add_node_gain(graph, "gain1"); - graph_set_source(graph, gain1, GAIN_INPUT, gain1, GAIN_RESULT); - int to_compute_for[1] = {gain1}; - graph_compute_nodes(graph, to_compute_for, 1); - return 0; -} diff --git a/quad/computation_graph/src/tests.h b/quad/computation_graph/src/tests.h deleted file mode 100644 index b30b7d806b88f3811b74f264742d4094cd4387c8..0000000000000000000000000000000000000000 --- a/quad/computation_graph/src/tests.h +++ /dev/null @@ -1,32 +0,0 @@ -// -// Created by dawehr on 2/9/2017. -// - -#ifndef COMPUTATION_GRAPH_TESTS_H -#define COMPUTATION_GRAPH_TESTS_H - -#include "computation_graph.h" -#include "graph_blocks/node_add.h" -#include "graph_blocks/node_mult.h" -#include "graph_blocks/node_constant.h" -#include "graph_blocks/node_gain.h" -#include "graph_blocks/node_accumulator.h" -#include <math.h> - -int graph_run_tests(); - -int graph_test_one_add(); - -int graph_test_circular_runs(); - -int graph_test_circular_resets(); - -int graph_test_self_loop(); - -int graph_test_accumulator(); - -int graph_test_single_run(); - -int graph_test_reset_rules(); - -#endif //COMPUTATION_GRAPH_TESTS_H diff --git a/quad/computation_graph/test/Makefile b/quad/computation_graph/test/Makefile deleted file mode 100644 index 4fb6cf11603044352c832c27ce2b2a21edc58147..0000000000000000000000000000000000000000 --- a/quad/computation_graph/test/Makefile +++ /dev/null @@ -1,12 +0,0 @@ -# QUAD_ROOT is obtained from environment -SRC = $(QUAD_ROOT)/computation_graph/src/graph_blocks/*.c $(QUAD_ROOT)/computation_graph/src/computation_graph.c -INC = $(QUAD_ROOT)/computation_graph/src -BLOCKS_INC = $(QUAD_ROOT)/computation_graph/src/graph_blocks -LIB = $(QUAD_ROOT)/lib/test - -test_computation_graph: test_computation_graph.c $(SRC) - gcc -o test_computation_graph -I. -I$(INC) -I$(BLOCKS_INC) -I$(LIB) $(LIB)/test.o test_computation_graph.c $(SRC) -lm - -.PHONY: clean -clean: - rm test_computation_graph diff --git a/quad/lib/test/.gitignore b/quad/lib/test/.gitignore deleted file mode 100644 index abf45b33b86643cbd0623e9265383923ef76e37e..0000000000000000000000000000000000000000 --- a/quad/lib/test/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -example -test.o \ No newline at end of file diff --git a/quad/lib/test/Makefile b/quad/lib/test/Makefile deleted file mode 100644 index b7b47546af040cb6eb6f326c71cad8026a9878e9..0000000000000000000000000000000000000000 --- a/quad/lib/test/Makefile +++ /dev/null @@ -1,9 +0,0 @@ -test.o: test.c - gcc -c test.c - -example: example.c test.c test.h - gcc -g -o example example.c test.c test.h - -.PHONY: clean -clean: - rm example test.o diff --git a/quad/library.mk b/quad/library.mk new file mode 100644 index 0000000000000000000000000000000000000000..1515d75b95fc3090178735e0877aa1ef878e54d8 --- /dev/null +++ b/quad/library.mk @@ -0,0 +1,55 @@ +GCC = gcc +AR = ar + +INCDIR = $(TOP)/inc +OBJDIR = obj +LIBDIR = $(TOP)/lib + +SOURCES = $(wildcard *.c) +TESTSOURCES = $(wildcard test/*.c) +HEADERS = $(wildcard *.h) +INCLUDES = $(addprefix $(INCDIR)/, $(HEADERS)) +OBJECTS = $(patsubst %.c, $(OBJDIR)/%.o, $(SOURCES)) +TESTOBJECTS = $(patsubst $.c, %.o, $(TESTSOURCES)) + +TARGET = $(LIBDIR)/lib$(NAME).a +TESTBIN = run_tests + +.PHONY: default test clean + +################ +## User Targets +################ + +default: $(TARGET) $(INCLUDES) + +test: $(TESTBIN) + ./$(TESTBIN) + +clean: + rm -rf $(TARGET) $(INCLUDES) $(OBJDIR) + +#################### +## Internal Targets +#################### + +$(TARGET): $(OBJECTS) | $(LIBDIR) + $(AR) rcs $@ $^ + +$(OBJDIR)/%.o : %.c | $(OBJDIR) $(INCDIR) + $(GCC) -c -g -o $@ $< -I$(INCDIR) + +$(INCDIR)/%.h : %.h | $(INCDIR) + cp $^ $(INCDIR) + +$(INCDIR): + mkdir $(INCDIR) + +$(OBJDIR): + mkdir $(OBJDIR) + +$(LIBDIR): + mkdir $(LIBDIR) + +$(TESTBIN): $(TESTOBJECTS) $(OBJECTS) | default + $(GCC) -g -o $(TESTBIN) $^ -I$(INCDIR) -L$(LIBDIR) $(REQLIBS) diff --git a/quad/scripts/build_zybo.sh b/quad/scripts/build_zybo.sh new file mode 100644 index 0000000000000000000000000000000000000000..f52dc500deff4454545fdf741434daa232204a01 --- /dev/null +++ b/quad/scripts/build_zybo.sh @@ -0,0 +1,14 @@ +#!/bin/bash + +set -e + +QUADDIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )"/.. && pwd )" +WS=$QUADDIR/xsdk_workspace + +PATH=$PATH:/remote/Xilinx/14.7:/opt/Xilinx/14.7/ISE_DS +source settings64.sh + +make -C $WS/system_bsp all +make -C $WS/modular_quad_pid/Release all +make -C $WS/zybo_fsbl_bsp all +make -C $WS/zybo_fsbl/Release all diff --git a/quad/scripts/clean_xsdk_workspace.sh b/quad/scripts/clean_xsdk_workspace.sh new file mode 100644 index 0000000000000000000000000000000000000000..656325d6e668f8bfbb85e98d743bf1f73dfa0a86 --- /dev/null +++ b/quad/scripts/clean_xsdk_workspace.sh @@ -0,0 +1,13 @@ +#!/bin/bash + +set -e + +QUADDIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )"/.. && pwd )" +WS=$QUADDIR/xsdk_workspace + +make -C $WS/modular_quad_pid/Debug clean +make -C $WS/modular_quad_pid/Release clean +make -C $WS/system_bsp clean +make -C $WS/zybo_fsbl/Debug clean +make -C $WS/zybo_fsbl/Release clean +make -C $WS/zybo_fsbl_bsp clean diff --git a/quad/scripts/create_zybo_boot.sh b/quad/scripts/create_zybo_boot.sh new file mode 100644 index 0000000000000000000000000000000000000000..5b1d5af820c752b9e1e6a548d1047ff300f75f60 --- /dev/null +++ b/quad/scripts/create_zybo_boot.sh @@ -0,0 +1,20 @@ +#!/bin/bash +set -e + +QUADDIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )"/.. && pwd )" +WS=$QUADDIR/xsdk_workspace + +PATH=$PATH:/remote/Xilinx/14.7:/opt/Xilinx/14.7/ISE_DS +source settings64.sh + +# Working directory: +cd $QUADDIR/out + +echo "the_ROM_image:" > zybo_fsbl.bif +echo "{" >> zybo_fsbl.bif +echo $WS/zybo_fsbl/Release/zybo_fsbl.elf >> zybo_fsbl.bif +echo $WS/system_hw_platform/system.bit >> zybo_fsbl.bif +echo $WS/modular_quad_pid/Release/modular_quad_pid.elf >> zybo_fsbl.bif +echo "}" >> zybo_fsbl.bif +bootgen -image zybo_fsbl.bif -o BOOT.bin +rm zybo_fsbl.bif \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/build.sh b/quad/scripts/old_quad_build.sh similarity index 59% rename from quad/sw/modular_quad_pid/build.sh rename to quad/scripts/old_quad_build.sh index 16f728e1c52a93f5b3996876765b2cc12919dc7c..2f8c4f6d6fefd7fa1b6912b4c3bbfa5295602a77 100644 --- a/quad/sw/modular_quad_pid/build.sh +++ b/quad/scripts/old_quad_build.sh @@ -1,5 +1,11 @@ #!/bin/bash +set -e + +Xvfb :1 -ac -screen 0 1024x768x8 & +VIRT_SCREEN=$! +export DISPLAY=:1 + source /remote/Xilinx/2015.4/SDK/2015.4/settings64.sh echo "Building modular_quad_pid" @@ -10,31 +16,42 @@ if [ ! -d ../.metadata ]; then ECLIPSE=/remote/Xilinx/2015.4/SDK/2015.4/eclipse/lnx64.o/eclipse VM=/remote/Xilinx/2015.4/SDK/2015.4/tps/lnx64/jre/bin WSPACE=$(dirname $0)/.. - HW=$WSPACE/system_hw_platform BSP=$WSPACE/system_bsp + FSBL=$WSPACE/zybo_fsbl + FSBL_BSP=$WSPACE/zybo_fsbl_bsp + HW=$WSPACE/system_hw_platform APP=$WSPACE/modular_quad_pid echo "Setting up dependencies for modular_quad_pid" - # Import the system_hw_platform into the workspace + # Import the system_hw_platform and app into the workspace $ECLIPSE -vm $VM -nosplash -application org.eclipse.cdt.managedbuilder.core.headlessbuild \ -import $HW \ + -import $APP \ -data $WSPACE \ - -vmargs -Dorg.eclipse.cdt.core.console=org.eclipse.cdt.core.systemConsole || exit 1 + -vmargs -Dorg.eclipse.cdt.core.console=org.eclipse.cdt.core.systemConsole # Create the BSP - xsct .create_bsp.tcl || exit 1 + xsct .create_bsp.tcl + + # Create the FSBL project + xsct .create_fsbl.tcl - # Import the system_bsp and modular_quad_pid into workspace $ECLIPSE -vm $VM -nosplash -application org.eclipse.cdt.managedbuilder.core.headlessbuild \ -import $BSP \ - -import $APP \ + -import $FSBL \ + -import $FSBL_BSP \ -data $WSPACE \ - -vmargs -Dorg.eclipse.cdt.core.console=org.eclipse.cdt.core.systemConsole || exit 1 + -vmargs -Dorg.eclipse.cdt.core.console=org.eclipse.cdt.core.systemConsole - # Build the BSP - xsct .build_bsp.tcl || exit 1 + # Build everything + $ECLIPSE -vm $VM -nosplash -application org.eclipse.cdt.managedbuilder.core.headlessbuild \ + -build all \ + -data $WSPACE \ + -vmargs -Dorg.eclipse.cdt.core.console=org.eclipse.cdt.core.systemConsole fi -xsct .build_app.tcl || exit 1 +xsct .build_app.tcl + +kill $VIRT_SCREEN diff --git a/quad/scripts/test_zybo_uart.py b/quad/scripts/test_zybo_uart.py new file mode 100755 index 0000000000000000000000000000000000000000..0ccd93c66f47df11e9ad87651e1299ca56f8453c --- /dev/null +++ b/quad/scripts/test_zybo_uart.py @@ -0,0 +1,24 @@ +#!/usr/local/bin/python3.6 + +import sys +import time + +import serial + +if __name__ == '__main__': + with serial.Serial('/dev/ttyUSB0', 921600, timeout=5) as ser: + ser.reset_input_buffer() + send_bytes = b'sdflouirgaorifa;eofija;ogijasfhluiasflawieufzxcvwe' + ser.write(send_bytes) + print("Sending {} bytes".format(len(send_bytes))) + time.sleep(1) + recv_bytes = bytes() + while ser.in_waiting != 0: + recv_bytes = ser.read(len(send_bytes)) + if recv_bytes == send_bytes: + print(recv_bytes); + print("Test Successful") + else: + print(recv_bytes); + print("Test Failed.") + diff --git a/quad/src/computation_graph/.gitignore b/quad/src/computation_graph/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..da2dc67a4f0e61a89b67664a64a475efc2adca6d --- /dev/null +++ b/quad/src/computation_graph/.gitignore @@ -0,0 +1,3 @@ +run_tests +obj/ +obj-zybo/ diff --git a/quad/src/computation_graph/Makefile b/quad/src/computation_graph/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..5142ac39b839e02ca6ed2eb2c28fcec186b88ef7 --- /dev/null +++ b/quad/src/computation_graph/Makefile @@ -0,0 +1,6 @@ +TOP=../.. + +NAME = computation_graph +REQLIBS = -ltest -lm + +include $(TOP)/library.mk diff --git a/quad/computation_graph/Makefile b/quad/src/computation_graph/Makefile_old similarity index 100% rename from quad/computation_graph/Makefile rename to quad/src/computation_graph/Makefile_old diff --git a/quad/computation_graph/src/computation_graph.c b/quad/src/computation_graph/computation_graph.c similarity index 99% rename from quad/computation_graph/src/computation_graph.c rename to quad/src/computation_graph/computation_graph.c index 5fcfd4c5c76ad7c221da927c410f45184c5c0578..7434e14a112117b8dbe22a3ecd300b04c6c90413 100644 --- a/quad/computation_graph/src/computation_graph.c +++ b/quad/src/computation_graph/computation_graph.c @@ -103,7 +103,7 @@ int graph_add_node(struct computation_graph *graph, new_node->n_children = 0; new_node->updated = 1; new_node->output_values = malloc(type->n_outputs * sizeof(double)); - new_node->param_values = malloc(type->n_params * sizeof(double)); + new_node->param_values = calloc(type->n_params, sizeof(double)); new_node->input_srcs = malloc(type->n_inputs * sizeof(struct input_type)); // Check that malloc succeeded in every case which memory was requested if ((type->n_outputs && !new_node->output_values) || diff --git a/quad/computation_graph/src/computation_graph.h b/quad/src/computation_graph/computation_graph.h similarity index 100% rename from quad/computation_graph/src/computation_graph.h rename to quad/src/computation_graph/computation_graph.h diff --git a/quad/computation_graph/src/graph_blocks/node_accumulator.c b/quad/src/computation_graph/node_accumulator.c similarity index 100% rename from quad/computation_graph/src/graph_blocks/node_accumulator.c rename to quad/src/computation_graph/node_accumulator.c diff --git a/quad/computation_graph/src/graph_blocks/node_accumulator.h b/quad/src/computation_graph/node_accumulator.h similarity index 90% rename from quad/computation_graph/src/graph_blocks/node_accumulator.h rename to quad/src/computation_graph/node_accumulator.h index 2df06c9d1c87473ed2bbb4fc6f8d40aa4b606318..a392a9db295e5bc7f44d84292e4aa561ee3fba9d 100644 --- a/quad/computation_graph/src/graph_blocks/node_accumulator.h +++ b/quad/src/computation_graph/node_accumulator.h @@ -1,6 +1,6 @@ #ifndef __NODE_ACCUMULATOR_H__ #define __NODE_ACCUMULATOR_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_accum(struct computation_graph *graph, const char* name); diff --git a/quad/computation_graph/src/graph_blocks/node_add.c b/quad/src/computation_graph/node_add.c similarity index 91% rename from quad/computation_graph/src/graph_blocks/node_add.c rename to quad/src/computation_graph/node_add.c index eefb22fde9ae9a5cc72d2eb679905f2e70038ac9..048a49b3b6a9c054f74900e356e6377f17a6a4b7 100644 --- a/quad/computation_graph/src/graph_blocks/node_add.c +++ b/quad/src/computation_graph/node_add.c @@ -8,7 +8,7 @@ static void reset(void *state) {} static const char* const in_names[2] = {"Summand 1", "Summand 2"}; static const char* const out_names[1] = {"Sum"}; -static const char* const param_names[0] = {}; +static const char* const param_names[1] = {"Error if you see this"}; const struct graph_node_type node_add_type = { .input_names = in_names, .output_names = out_names, diff --git a/quad/computation_graph/src/graph_blocks/node_add.h b/quad/src/computation_graph/node_add.h similarity index 90% rename from quad/computation_graph/src/graph_blocks/node_add.h rename to quad/src/computation_graph/node_add.h index cfd2b71e8b25aecfa38898dbce8427ad97bf6ff9..390e3d229c7a943fdd09c26e18be711672cf000e 100644 --- a/quad/computation_graph/src/graph_blocks/node_add.h +++ b/quad/src/computation_graph/node_add.h @@ -1,6 +1,6 @@ #ifndef __NODE_ADD_H__ #define __NODE_ADD_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_add(struct computation_graph *graph, const char* name); diff --git a/quad/computation_graph/src/graph_blocks/node_constant.c b/quad/src/computation_graph/node_constant.c similarity index 91% rename from quad/computation_graph/src/graph_blocks/node_constant.c rename to quad/src/computation_graph/node_constant.c index 8ad9f8c5afdb5dc8f4cfacac00f2725ad388a59a..b2a46e757eef397b4c9805d4b76a159fccc6c9a0 100644 --- a/quad/computation_graph/src/graph_blocks/node_constant.c +++ b/quad/src/computation_graph/node_constant.c @@ -6,7 +6,7 @@ static void output_const(void *state, const double *params, const double *inputs } static void reset(void *state) {} -static const char* const in_names[0] = {}; +static const char* const in_names[1] = {"You shouldn't see this"}; static const char* const out_names[1] = {"Constant"}; static const char* const param_names[1] = {"Constant"}; const struct graph_node_type node_const_type = { diff --git a/quad/computation_graph/src/graph_blocks/node_constant.h b/quad/src/computation_graph/node_constant.h similarity index 90% rename from quad/computation_graph/src/graph_blocks/node_constant.h rename to quad/src/computation_graph/node_constant.h index 91cd6d055b6bbf64340df4282ac9f9539301f0a5..c67ac6e0511e971e1f9ca57c853bd9de6fca6238 100644 --- a/quad/computation_graph/src/graph_blocks/node_constant.h +++ b/quad/src/computation_graph/node_constant.h @@ -1,6 +1,6 @@ #ifndef __NODE_CONSTANT_H__ #define __NODE_CONSTANT_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_const(struct computation_graph *graph, const char* name); diff --git a/quad/computation_graph/src/graph_blocks/node_gain.c b/quad/src/computation_graph/node_gain.c similarity index 100% rename from quad/computation_graph/src/graph_blocks/node_gain.c rename to quad/src/computation_graph/node_gain.c diff --git a/quad/computation_graph/src/graph_blocks/node_gain.h b/quad/src/computation_graph/node_gain.h similarity index 91% rename from quad/computation_graph/src/graph_blocks/node_gain.h rename to quad/src/computation_graph/node_gain.h index b26d3bfe393468c686f8b5b73957e1604594e5d0..4089244980ad7ee2fc50bc375f6cbb1500196b5e 100644 --- a/quad/computation_graph/src/graph_blocks/node_gain.h +++ b/quad/src/computation_graph/node_gain.h @@ -1,6 +1,6 @@ #ifndef __NODE_GAIN_H__ #define __NODE_GAIN_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_gain(struct computation_graph *graph, const char* name); diff --git a/quad/computation_graph/src/graph_blocks/node_mult.c b/quad/src/computation_graph/node_mult.c similarity index 100% rename from quad/computation_graph/src/graph_blocks/node_mult.c rename to quad/src/computation_graph/node_mult.c diff --git a/quad/computation_graph/src/graph_blocks/node_mult.h b/quad/src/computation_graph/node_mult.h similarity index 90% rename from quad/computation_graph/src/graph_blocks/node_mult.h rename to quad/src/computation_graph/node_mult.h index 32d2d873d359ae10bdff6dc857bab6d835c04598..9ea2bbb9fabdbc522a02f292f5294b33ad7af44c 100644 --- a/quad/computation_graph/src/graph_blocks/node_mult.h +++ b/quad/src/computation_graph/node_mult.h @@ -1,6 +1,6 @@ #ifndef __NODE_MULT_H__ #define __NODE_MULT_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_mult(struct computation_graph *graph, const char* name); diff --git a/quad/computation_graph/src/graph_blocks/node_pow.c b/quad/src/computation_graph/node_pow.c similarity index 100% rename from quad/computation_graph/src/graph_blocks/node_pow.c rename to quad/src/computation_graph/node_pow.c diff --git a/quad/computation_graph/src/graph_blocks/node_pow.h b/quad/src/computation_graph/node_pow.h similarity index 90% rename from quad/computation_graph/src/graph_blocks/node_pow.h rename to quad/src/computation_graph/node_pow.h index 11bdd9173c7522683e3b8af7fec809632b856c19..56a73d3d05fe12f22b16ae248a22347647f95ae0 100644 --- a/quad/computation_graph/src/graph_blocks/node_pow.h +++ b/quad/src/computation_graph/node_pow.h @@ -1,6 +1,6 @@ #ifndef __NODE_POW_H__ #define __NODE_POW_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_pow(struct computation_graph *graph, const char* name); diff --git a/quad/computation_graph/test/test_computation_graph.c b/quad/src/computation_graph/test/test_computation_graph.c similarity index 97% rename from quad/computation_graph/test/test_computation_graph.c rename to quad/src/computation_graph/test/test_computation_graph.c index 9d7c96bbc4c42349978b13d62c7d7036d20b516c..1948421eb7c8792756c51e4cccd6f8c559f0ac95 100644 --- a/quad/computation_graph/test/test_computation_graph.c +++ b/quad/src/computation_graph/test/test_computation_graph.c @@ -2,11 +2,11 @@ #include "computation_graph.h" -#include "graph_blocks/node_add.h" -#include "graph_blocks/node_mult.h" -#include "graph_blocks/node_constant.h" -#include "graph_blocks/node_gain.h" -#include "graph_blocks/node_accumulator.h" +#include "node_add.h" +#include "node_mult.h" +#include "node_constant.h" +#include "node_gain.h" +#include "node_accumulator.h" #define GRAPH_TEST_EPS 0.00001 @@ -229,5 +229,5 @@ int main() { test(graph_test_update_rules, "Tests that nodes only update when their inputs change"); test(graph_test_update_propagation, "Tests that updates propagate only to their children"); test(graph_test_update_disconnected, "Tests that nodes get executed when updated, even if disconnected"); - test_summary(); + return test_summary(); } diff --git a/quad/sw/modular_quad_pid/gen_diagram/.gitignore b/quad/src/gen_diagram/.gitignore similarity index 100% rename from quad/sw/modular_quad_pid/gen_diagram/.gitignore rename to quad/src/gen_diagram/.gitignore diff --git a/quad/sw/modular_quad_pid/gen_diagram/Makefile b/quad/src/gen_diagram/Makefile similarity index 100% rename from quad/sw/modular_quad_pid/gen_diagram/Makefile rename to quad/src/gen_diagram/Makefile diff --git a/quad/sw/modular_quad_pid/gen_diagram/README.md b/quad/src/gen_diagram/README.md similarity index 100% rename from quad/sw/modular_quad_pid/gen_diagram/README.md rename to quad/src/gen_diagram/README.md diff --git a/quad/sw/modular_quad_pid/gen_diagram/create_png.sh b/quad/src/gen_diagram/create_png.sh old mode 100644 new mode 100755 similarity index 71% rename from quad/sw/modular_quad_pid/gen_diagram/create_png.sh rename to quad/src/gen_diagram/create_png.sh index c431622d50d7ea3c0b6a5673896d8eea1bec5cef..3389781bf0d69d913c2b8d10e055ff2945bc3846 --- a/quad/sw/modular_quad_pid/gen_diagram/create_png.sh +++ b/quad/src/gen_diagram/create_png.sh @@ -1,4 +1,7 @@ #/bin/bash +make +./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 new file mode 100755 index 0000000000000000000000000000000000000000..8413df5adf030804107bf812502da5249bf17b24 Binary files /dev/null and b/quad/src/gen_diagram/gen_diagram differ diff --git a/quad/sw/modular_quad_pid/gen_diagram/generate.c b/quad/src/gen_diagram/generate.c similarity index 74% rename from quad/sw/modular_quad_pid/gen_diagram/generate.c rename to quad/src/gen_diagram/generate.c index f04b94717b487b30a0c2338a3a1a66e9d761312d..da5f3c3835bba723c55999d257a935ddf340aa6c 100644 --- a/quad/sw/modular_quad_pid/gen_diagram/generate.c +++ b/quad/src/gen_diagram/generate.c @@ -1,10 +1,10 @@ #include <stdio.h> #include "computation_graph.h" -#include "graph_blocks/node_pid.h" -#include "graph_blocks/node_bounds.h" -#include "graph_blocks/node_constant.h" -#include "graph_blocks/node_mixer.h" +#include "node_pid.h" +#include "node_bounds.h" +#include "node_constant.h" +#include "node_mixer.h" #include "PID.h" #include "control_algorithm.h" diff --git a/quad/sw/modular_quad_pid/gen_diagram/local_PID.h b/quad/src/gen_diagram/local_PID.h similarity index 100% rename from quad/sw/modular_quad_pid/gen_diagram/local_PID.h rename to quad/src/gen_diagram/local_PID.h diff --git a/quad/sw/modular_quad_pid/gen_diagram/network.dot b/quad/src/gen_diagram/network.dot similarity index 83% rename from quad/sw/modular_quad_pid/gen_diagram/network.dot rename to quad/src/gen_diagram/network.dot index 711d7dd16753ba44337053c960bb6d0f8fc15912..6c7ff17339d512cd4468ece1ac8c74a7e7b86183 100644 --- a/quad/sw/modular_quad_pid/gen_diagram/network.dot +++ b/quad/src/gen_diagram/network.dot @@ -2,49 +2,49 @@ 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]"] -"Roll" -> "Roll PID":f1 [label="Constant"] -"RC Roll" -> "Roll PID":f2 [label="Constant"] -"Ts_angle" -> "Roll PID":f3 [label="Constant"] +"VRPN Roll" -> "Roll PID":f1 [label="Constant"] +"Y pos PID" -> "Roll PID":f2 [label="Correction"] +"Ts_VRPN" -> "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]"] -"Pitch" -> "Pitch PID":f1 [label="Constant"] -"RC Pitch" -> "Pitch PID":f2 [label="Constant"] -"Ts_angle" -> "Pitch PID":f3 [label="Constant"] +"VRPN Pitch" -> "Pitch PID":f1 [label="Constant"] +"X pos PID" -> "Pitch PID":f2 [label="Correction"] +"Ts_VRPN" -> "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]"] "Yaw" -> "Yaw PID":f1 [label="Constant"] "Yaw Setpoint" -> "Yaw PID":f2 [label="Constant"] -"Ts_angle" -> "Yaw PID":f3 [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]"] "dPhi" -> "Roll Rate PID":f1 [label="Constant"] "Roll PID" -> "Roll Rate PID":f2 [label="Correction"] -"Ts_angle" -> "Roll Rate PID":f3 [label="Constant"] +"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]"] "dTheta" -> "Pitch Rate PID":f1 [label="Constant"] "Pitch PID" -> "Pitch Rate PID":f2 [label="Correction"] -"Ts_angle" -> "Pitch Rate PID":f3 [label="Constant"] +"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]"] "dPsi" -> "Yaw Rate PID":f1 [label="Constant"] -"RC Yaw" -> "Yaw Rate PID":f2 [label="Constant"] -"Ts_angle" -> "Yaw Rate PID":f3 [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]"] "VRPN X" -> "X pos PID":f1 [label="Constant"] "X Setpoint" -> "X pos PID":f2 [label="Constant"] -"Ts_position" -> "X pos PID":f3 [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]"] "VRPN Y" -> "Y pos PID":f1 [label="Constant"] "Y Setpoint" -> "Y pos PID":f2 [label="Constant"] -"Ts_position" -> "Y pos PID":f3 [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]"] "VRPN Alt" -> "Altitude PID":f1 [label="Constant"] "Alt Setpoint" -> "Altitude PID":f2 [label="Constant"] -"Ts_position" -> "Altitude PID":f3 [label="Constant"] +"Ts_VRPN" -> "Altitude PID":f3 [label="Constant"] "X Setpoint"[shape=record label="<f0>X Setpoint |<f1> [Constant=0.000]"] "Y Setpoint"[shape=record @@ -100,12 +100,11 @@ 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"] -"RC Throttle" -> "Signal Mixer":f1 [label="Constant"] "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_angle"[shape=record -label="<f0>Ts_angle |<f1> [Constant=0.005]"] -"Ts_position"[shape=record -label="<f0>Ts_position |<f1> [Constant=0.100]"] +"Ts_IMU"[shape=record +label="<f0>Ts_IMU |<f1> [Constant=0.000]"] +"Ts_VRPN"[shape=record +label="<f0>Ts_VRPN |<f1> [Constant=0.000]"] } \ No newline at end of file diff --git a/quad/src/gen_diagram/network.png b/quad/src/gen_diagram/network.png new file mode 100644 index 0000000000000000000000000000000000000000..6734445acec05b986f97fb83855e62a39ee27463 Binary files /dev/null and b/quad/src/gen_diagram/network.png differ diff --git a/quad/src/quad_app/.gitignore b/quad/src/quad_app/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..021c5c0aeb97a90bc0555e3bf63cbc18a01a9f8f --- /dev/null +++ b/quad/src/quad_app/.gitignore @@ -0,0 +1,3 @@ +obj-zybo/ +obj/ +run_tests \ No newline at end of file diff --git a/quad/src/quad_app/Makefile b/quad/src/quad_app/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..aea2974582bf7a794b8b32ecdd46223260d26470 --- /dev/null +++ b/quad/src/quad_app/Makefile @@ -0,0 +1,6 @@ +TOP=../.. + +NAME = quad_app +REQLIBS = -ltest -lcomputation_graph -lm -lqueue + +include $(TOP)/library.mk diff --git a/quad/sw/imu_logger/src/PID.c b/quad/src/quad_app/PID.c similarity index 100% rename from quad/sw/imu_logger/src/PID.c rename to quad/src/quad_app/PID.c diff --git a/quad/sw/modular_quad_pid/src/PID.h b/quad/src/quad_app/PID.h similarity index 98% rename from quad/sw/modular_quad_pid/src/PID.h rename to quad/src/quad_app/PID.h index a7701ab2a8a8701343d4e65d5688759d70aba2b9..4c5e4b81f0273a9a62aa175b6c0f350914fb67a2 100644 --- a/quad/sw/modular_quad_pid/src/PID.h +++ b/quad/src/quad_app/PID.h @@ -49,6 +49,7 @@ #define YPOS_KP 0.015f #define YPOS_KI 0.005f #define YPOS_KD 0.03f +#define YPOS_ALPHA 0 //Pitch constants @@ -74,6 +75,7 @@ #define XPOS_KP -0.015f #define XPOS_KI -0.005f #define XPOS_KD -0.03f +#define XPOS_ALPHA 0 //Throttle constants diff --git a/quad/sw/imu_logger/src/README.txt b/quad/src/quad_app/README.txt similarity index 100% rename from quad/sw/imu_logger/src/README.txt rename to quad/src/quad_app/README.txt diff --git a/quad/sw/modular_quad_pid/src/actuator_command_processing.c b/quad/src/quad_app/actuator_command_processing.c similarity index 100% rename from quad/sw/modular_quad_pid/src/actuator_command_processing.c rename to quad/src/quad_app/actuator_command_processing.c diff --git a/quad/sw/imu_logger/src/actuator_command_processing.h b/quad/src/quad_app/actuator_command_processing.h similarity index 100% rename from quad/sw/imu_logger/src/actuator_command_processing.h rename to quad/src/quad_app/actuator_command_processing.h diff --git a/quad/sw/modular_quad_pid/src/callbacks.c b/quad/src/quad_app/callbacks.c similarity index 74% rename from quad/sw/modular_quad_pid/src/callbacks.c rename to quad/src/quad_app/callbacks.c index 36f393434b9da690ec03e2532e415055955f1719..183ecf85458ee8233f30ab0c6afdc688cfc7a983 100644 --- a/quad/sw/modular_quad_pid/src/callbacks.c +++ b/quad/src/quad_app/callbacks.c @@ -1,8 +1,8 @@ #include "communication.h" #include "commands.h" #include "type_def.h" -#include "uart.h" #include "computation_graph.h" +#include "util.h" /* * Static variables used to keep track of packet counts @@ -16,26 +16,26 @@ static size_t total_payload_received = 0; /** * Currently does nothing. */ -int cb_debug(modular_structs_t *structs) +int cb_debug(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) { char buf[255]; // Get the node ID, parameter ID, parameter value - u8 node_id = uart_buff_data_get_u8(0); + u8 node_id = data[0]; struct computation_graph* graph = structs->parameter_struct.graph; float param_val = graph_get_output(graph, node_id, 0); - int length = snprintf(buf, sizeof buf, "%f", param_val); - send_data(DEBUG_ID, 0, buf, length >= sizeof(buf) ? 255 : length + 1); + int len = snprintf(buf, sizeof buf, "%f", param_val); + send_data(&structs->hardware_struct.uart, DEBUG_ID, 0, buf, len >= sizeof(buf) ? 255 : length + 1); return 0; } /** * counts the number of packet logs. */ -int cb_packetlog(modular_structs_t* structs) { +int cb_packetlog(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { n_msg_received += 1; - total_payload_received += uart_buff_data_length(); + total_payload_received += length; return 0; } @@ -43,38 +43,38 @@ int cb_packetlog(modular_structs_t* structs) { * Handles a get packet logs request and sends a response * with the packet log data. */ -int cb_getpacketlogs(modular_structs_t* structs) { +int cb_getpacketlogs(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { char buf[255]; // Message logging number of messages received and size of payload received - int length = snprintf(buf, sizeof buf, "%d,%d", n_msg_received, total_payload_received); + int len = snprintf(buf, sizeof buf, "%d,%d", n_msg_received, total_payload_received); - send_data(LOG_ID, 0, buf, length >= sizeof(buf) ? 255 : length + 1); + send_data(&structs->hardware_struct.uart, LOG_ID, 0, buf, len >= sizeof(buf) ? 255 : len + 1); return 0; } /* * Handles receiving new location updates. */ -int cb_update(modular_structs_t *structs) +int cb_update(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) { //processUpdate(packet, &(structs->raw_sensor_struct.currentQuadPosition)); quadPosition_t* currentQuadPosition = &(structs->raw_sensor_struct.currentQuadPosition); // Packet must come as [NEARPY], 4 bytes each - int packetId = uart_buff_data_get_u32(0); + int packetId = build_int(data + 0); // printf("Packet ID: %d\n", packetId); - float y_pos = uart_buff_data_get_float(4); + float y_pos = build_float(data + 4); // printf("y_pos: %f\n", y_pos); - float x_pos = uart_buff_data_get_float(8); + float x_pos = build_float(data + 8); // printf("x_pos: %f\n", x_pos); - float alt_pos = uart_buff_data_get_float(12); + float alt_pos = build_float(data + 12); // printf("alt_pos: %f\n", alt_pos); - float roll = uart_buff_data_get_float(16); + float roll = build_float(data + 16); // printf("roll: %f\n", roll); - float pitch = uart_buff_data_get_float(20); + float pitch = build_float(data + 20); // printf("pitch: %f\n", pitch); - float yaw = uart_buff_data_get_float(24); + float yaw = build_float(data + 24); // printf("yaw: %f\n", yaw); currentQuadPosition->packetId = packetId; @@ -94,7 +94,7 @@ int cb_update(modular_structs_t *structs) /** * This is called on the ground station to begin sending VRPN to the quad. */ -int cb_beginupdate(modular_structs_t *structs) { +int cb_beginupdate(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) { structs->user_input_struct.receivedBeginUpdate = 1; return 0; } @@ -117,10 +117,10 @@ int cb_beginupdate(modular_structs_t *structs) { * * Does not send anything in response. */ -int cb_setparam(modular_structs_t *structs) +int cb_setparam(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) { // Get some of the meta data - u16 data_len = uart_buff_data_length(); + u16 data_len = length; // Check if the data length is correct if (data_len != 6) { @@ -129,9 +129,9 @@ int cb_setparam(modular_structs_t *structs) struct computation_graph* graph = structs->parameter_struct.graph; // Get the node ID, parameter ID, parameter value - u8 node_id = uart_buff_data_get_u8(0); - u8 param_id = uart_buff_data_get_u8(1); - float param_val = uart_buff_data_get_float(2); + u8 node_id = data[0]; + u8 param_id = data[1]; + float param_val = build_float(data + 2); // Set the value for that parameter on that node graph_set_param_val(graph, node_id, param_id, param_val); @@ -162,11 +162,11 @@ int cb_setparam(modular_structs_t *structs) * | bytes || 1 | 1 | 4 | * |--------------------------------------------------------| */ -int cb_getparam(modular_structs_t* structs) +int cb_getparam(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) { // Get some of the meta data - u16 data_len = uart_buff_data_length(); - u16 msg_id = uart_buff_get_u16(3); + u16 data_len = length; + u16 msg_id = meta->msg_id; // Check if the data length is correct if (data_len != 2) { @@ -174,8 +174,8 @@ int cb_getparam(modular_structs_t* structs) } // Get the controller ID, parameter ID - u8 node_id = uart_buff_data_get_u8(0); - u8 param_id = uart_buff_data_get_u8(1); + u8 node_id = data[0]; + u8 param_id = data[1]; struct computation_graph* graph = structs->parameter_struct.graph; float param_val = graph_get_param_val(graph, node_id, param_id); @@ -190,7 +190,7 @@ int cb_getparam(modular_structs_t* structs) memcpy(&resp_data[2], ¶m_val, sizeof(param_val)); // Send the response - send_data(RESPPARAM_ID, msg_id, resp_data, sizeof(resp_data)); + send_data(&structs->hardware_struct.uart, RESPPARAM_ID, msg_id, resp_data, sizeof(resp_data)); return 0; } diff --git a/quad/sw/modular_quad_pid/src/callbacks.h b/quad/src/quad_app/callbacks.h similarity index 55% rename from quad/sw/modular_quad_pid/src/callbacks.h rename to quad/src/quad_app/callbacks.h index 7e67ddac5b59b5e824faf8a2a6bb736609242fca..80d0bbc43a5634cf176d084292ddae0376599773 100644 --- a/quad/sw/modular_quad_pid/src/callbacks.h +++ b/quad/src/quad_app/callbacks.h @@ -2,10 +2,10 @@ #define __callbacks_h /* Grab some stupid stuff from legacy code */ - struct modular_structs; +struct metadata; /* Make commands.c happy */ -typedef int (command_cb)(struct modular_structs *structs); +typedef int (command_cb)(struct modular_structs *, struct metadata *, unsigned char *, unsigned short); #endif diff --git a/quad/sw/modular_quad_pid/src/cb_default.h b/quad/src/quad_app/cb_default.h similarity index 100% rename from quad/sw/modular_quad_pid/src/cb_default.h rename to quad/src/quad_app/cb_default.h diff --git a/quad/src/quad_app/commands.c b/quad/src/quad_app/commands.c new file mode 120000 index 0000000000000000000000000000000000000000..e9bada254a300676bc4a563b5d1183e02125693f --- /dev/null +++ b/quad/src/quad_app/commands.c @@ -0,0 +1 @@ +../../../groundStation/src/backend/common/commands.c \ No newline at end of file diff --git a/quad/src/quad_app/commands.h b/quad/src/quad_app/commands.h new file mode 120000 index 0000000000000000000000000000000000000000..92d6b32d4641fd6b8ea711d7141b7b03d484b72a --- /dev/null +++ b/quad/src/quad_app/commands.h @@ -0,0 +1 @@ +../../../groundStation/src/backend/common/commands.h \ No newline at end of file diff --git a/quad/src/quad_app/communication.c b/quad/src/quad_app/communication.c new file mode 100644 index 0000000000000000000000000000000000000000..619257cb062e480d32146abaeecceba3021cc1cc --- /dev/null +++ b/quad/src/quad_app/communication.c @@ -0,0 +1,143 @@ +#include "communication.h" + +#define INTC XScuGic +#define COMM_UART_DEVICE_ID XPAR_PS7_UART_0_DEVICE_ID +#define COMM_INTC_DEVICE_ID XPAR_SCUGIC_SINGLE_DEVICE_ID +#define COMM_UART_INT_IRQ_ID XPAR_PS7_UART_0_INTR//XPAR_XUARTPS_0_INTR + +#define BAUD_RATE 921600 +// Maximum number of bytes to be received within our loop time, +// plus the maximum packet size that might be carried over from the last call, +// plus 128 for a little buffer +// (bit/s) * (seconds) / (10 bits / byte for UART) +#define PACKET_HEADER_SIZE 7 +#define UART_BUF_SIZE (((BAUD_RATE * (DESIRED_USEC_PER_LOOP / 1000) / 1000) / 10) + MAX_PACKET_SIZE + 128) + +//#define INTERRUPT_BENCHMARK + +// Declaration of interrupt handler +void Handler(void *CallBackRef, u32 Event, unsigned int EventData); + +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 + if (bytes_recv == 0) { + if (uart->read(uart, &packet[bytes_recv])) return -1; // uart empty + if (packet[bytes_recv] != 0xBE) { + continue; // keep looking + } + bytes_recv = 1; + } + + // receive length bytes + while (bytes_recv < PACKET_HEADER_SIZE) { + if (uart->read(uart, &packet[bytes_recv])) return -1; // uart empty + bytes_recv += 1; + } + + // Check if incoming packet is nonsensically large + unsigned short length = (packet[6] << 8 | packet[5]) + PACKET_HEADER_SIZE; + if (length >= MAX_PACKET_SIZE) { + bytes_recv = 0; + continue; // abort packet and start over + } + + // Receive rest of packet + while (bytes_recv < length) { + if (uart->read(uart, &packet[bytes_recv])) return -1; // uart empty + bytes_recv += 1; + } + + // Receive checksum and compare + if (bytes_recv < length + 1) { + if (uart->read(uart, &packet[bytes_recv])) return -1; // uart empty + unsigned char calculated_checksum = 0; + int i; + for(i = 0; i < length; i++) { + calculated_checksum ^= packet[i]; + } + if (calculated_checksum != packet[bytes_recv]) { + bytes_recv = 0; + continue; // abort packet and start over + } + bytes_recv += 1; + } + + // Packet ready + return 0; + } + + // Try again later + return -1; +} + +int process_packet(modular_structs_t *structs) { + metadata_t meta; + // parse metadata + meta.begin_char = packet[0]; + meta.msg_type = packet[2] << 8 | packet[1]; + meta.msg_id = packet[4] << 8 | packet[3]; + meta.data_len = packet[6] << 8 | packet[5]; + unsigned char packet_checksum = packet[7+meta.data_len]; + + // Call appropriate function for packet + (* (MessageTypes[meta.msg_type].functionPtr))(structs,&meta,&packet[PACKET_HEADER_SIZE], meta.data_len); + + // Done processing packets, reset state + bytes_recv = 0; + + return 0; +} + +void process_received(modular_structs_t *structs) { + // Parse as many packets as possible + struct UARTDriver *uart = &structs->hardware_struct.uart; + while (!try_receive_packet(uart)) { + process_packet(structs); + } +} + +int send_data(struct UARTDriver *uart, u16 type_id, u16 msg_id, char* data, size_t size) { + //---------------------------------------------------------------------------------------------- + // index|| 0 | 1 | 2 | 3 & 4 | 5 & 6 | 7+ | end | + //---------------------------------------------------------------------------------------------| + // msg param|| beg char | msg type | msg id | data len (bytes) | data | checksum | + //-------------------------------------------------------------------------------------------- | + // bytes|| 1 | 2 | 2 | 2 | var | 1 | + //---------------------------------------------------------------------------------------------- + + unsigned char formattedHeader[PACKET_HEADER_SIZE]; + + // Begin Char: + formattedHeader[0] = BEGIN_CHAR; + // Msg type 2 bytes: + formattedHeader[1] = type_id & 0x000000ff; + formattedHeader[2] = (type_id >> 8) & 0x000000ff; + // Msg id 2 bytes + formattedHeader[3] = msg_id & 0x000000ff; + formattedHeader[4] = (msg_id >> 8) & 0x000000ff; + // Data length and data - bytes 5&6 for len, 7+ for data + formattedHeader[5] = size & 0x000000ff; + formattedHeader[6] = (size >> 8) & 0x000000ff; + + // Compute checksum + unsigned char packet_checksum = 0; + int i; + for(i = 0; i < PACKET_HEADER_SIZE; i++) { + packet_checksum ^= formattedHeader[i]; + uart->write(uart, formattedHeader[i]); + } + for (i = 0; i < size; i++) { + packet_checksum ^= data[i]; + uart->write(uart, (unsigned char) data[i]); + } + + uart->write(uart, packet_checksum); + + return 0; +} diff --git a/quad/src/quad_app/communication.h b/quad/src/quad_app/communication.h new file mode 100644 index 0000000000000000000000000000000000000000..8655aad007e1406774d1a70cf2ed130faac4f426 --- /dev/null +++ b/quad/src/quad_app/communication.h @@ -0,0 +1,15 @@ +#ifndef _COMMUNICATION_H +#define _COMMUNICATION_H + +#include "type_def.h" +#include "timer.h" +#include "commands.h" +#include "hw_iface.h" + +#define MAX_PACKET_SIZE 256 + +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); + +#endif diff --git a/quad/sw/modular_quad_pid/src/control_algorithm.c b/quad/src/quad_app/control_algorithm.c similarity index 92% rename from quad/sw/modular_quad_pid/src/control_algorithm.c rename to quad/src/quad_app/control_algorithm.c index bc2f193ae88ba91f08ea9379282c9c41688e9528..5e1ebfd7dd227de54ab2ec80b02896b02d26694b 100644 --- a/quad/sw/modular_quad_pid/src/control_algorithm.c +++ b/quad/src/quad_app/control_algorithm.c @@ -8,11 +8,11 @@ // This implemented modular quadrotor software implements a PID control algorithm #include "control_algorithm.h" -#include "graph_blocks/node_pid.h" -#include "graph_blocks/node_bounds.h" -#include "graph_blocks/node_constant.h" -#include "graph_blocks/node_mixer.h" -#include "graph_blocks/node_add.h" +#include "node_pid.h" +#include "node_bounds.h" +#include "node_constant.h" +#include "node_mixer.h" +#include "node_add.h" #include "PID.h" #include "util.h" #include "timer.h" @@ -26,7 +26,7 @@ void connect_autonomous(parameter_t* ps) { 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->yaw_r_pid, PID_SETPOINT, ps->yaw_pid, PID_CORRECTION); + graph_set_source(graph, ps->yaw_r_pid, PID_SETPOINT, ps->yaw_pid, PID_CORRECTION); } void connect_manual(parameter_t* ps) { @@ -90,23 +90,23 @@ int control_algorithm_init(parameter_t * ps) ps->mixer = graph_add_node_mixer(graph, "Signal Mixer"); - ps->angle_time = graph_add_node_const(graph, "Ts_angle"); - ps->pos_time = graph_add_node_const(graph, "Ts_position"); + ps->angle_time = graph_add_node_const(graph, "Ts_IMU"); + ps->pos_time = graph_add_node_const(graph, "Ts_VRPN"); // Connect pitch PID chain 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_SETPOINT, ps->rc_pitch, 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->vrpn_pitch, CONST_VAL); graph_set_source(graph, ps->pitch_pid, PID_DT, ps->angle_time, CONST_VAL); // Connect roll PID chain graph_set_source(graph, ps->roll_r_pid, PID_SETPOINT, ps->roll_pid, PID_CORRECTION); graph_set_source(graph, ps->roll_r_pid, PID_CUR_POINT, ps->phi_dot, CONST_VAL); graph_set_source(graph, ps->roll_r_pid, PID_DT, ps->angle_time, CONST_VAL); - //graph_set_source(graph, ps->roll_pid, PID_SETPOINT, ps->rc_roll, CONST_VAL); graph_set_source(graph, ps->roll_pid, PID_CUR_POINT, ps->cur_roll, CONST_VAL); + //graph_set_source(graph, ps->roll_pid, PID_CUR_POINT, ps->vrpn_roll, CONST_VAL); graph_set_source(graph, ps->roll_pid, PID_DT, ps->angle_time, CONST_VAL); // Connect yaw PID chain @@ -131,7 +131,7 @@ int control_algorithm_init(parameter_t * ps) graph_set_source(graph, ps->throttle_trim_add, ADD_SUMMAND1, ps->alt_pid, PID_CORRECTION); graph_set_source(graph, ps->throttle_trim_add, ADD_SUMMAND2, ps->throttle_trim, CONST_VAL); // Yaw autonomous - graph_set_source(graph, ps->yaw_pid, PID_DT, ps->angle_time, CONST_VAL); + graph_set_source(graph, ps->yaw_pid, PID_DT, ps->pos_time, CONST_VAL); graph_set_source(graph, ps->yaw_pid, PID_SETPOINT, ps->yaw_set, CONST_VAL); graph_set_source(graph, ps->yaw_pid, PID_CUR_POINT, ps->cur_yaw, CONST_VAL); @@ -174,9 +174,11 @@ int control_algorithm_init(parameter_t * ps) graph_set_param_val(graph, ps->x_pos_pid, PID_KP, XPOS_KP); graph_set_param_val(graph, ps->x_pos_pid, PID_KI, XPOS_KI); graph_set_param_val(graph, ps->x_pos_pid, PID_KD, XPOS_KD); + graph_set_param_val(graph, ps->x_pos_pid, PID_ALPHA, XPOS_ALPHA); graph_set_param_val(graph, ps->y_pos_pid, PID_KP, YPOS_KP); graph_set_param_val(graph, ps->y_pos_pid, PID_KI, YPOS_KI); graph_set_param_val(graph, ps->y_pos_pid, PID_KD, YPOS_KD); + graph_set_param_val(graph, ps->y_pos_pid, PID_ALPHA, YPOS_ALPHA); graph_set_param_val(graph, ps->alt_pid, PID_KP, ALT_ZPOS_KP); graph_set_param_val(graph, ps->alt_pid, PID_KI, ALT_ZPOS_KI); graph_set_param_val(graph, ps->alt_pid, PID_KD, ALT_ZPOS_KD); @@ -189,6 +191,10 @@ int control_algorithm_init(parameter_t * ps) graph_set_param_val(graph, ps->clamp_d_pwmY, BOUNDS_MIN, -PWM_DIFF_BOUNDS); graph_set_param_val(graph, ps->clamp_d_pwmY, BOUNDS_MAX, PWM_DIFF_BOUNDS); + + // 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); // Set initial mode connect_manual(ps); @@ -243,7 +249,7 @@ int control_algorithm_init(parameter_t * ps) user_defined_struct->flight_mode = AUTO_FLIGHT_MODE; connect_autonomous(ps); // Reset this when autonomous is engaged, so there is not a large difference at the start of autonomous - last_vrpn_id = sensor_struct->currentQuadPosition.packetId; + last_vrpn_id = sensor_struct->currentQuadPosition.packetId - 1; } //PIDS/////////////////////////////////////////////////////////////////////// @@ -275,9 +281,13 @@ int control_algorithm_init(parameter_t * ps) // Sensor values graph_set_param_val(graph, ps->cur_pitch, CONST_SET, sensor_struct->pitch_angle_filtered); graph_set_param_val(graph, ps->cur_roll, CONST_SET, sensor_struct->roll_angle_filtered); - graph_set_param_val(graph, ps->theta_dot, CONST_SET, sensor_struct->theta_dot); - graph_set_param_val(graph, ps->phi_dot, CONST_SET, sensor_struct->phi_dot); - graph_set_param_val(graph, ps->psi_dot, CONST_SET, sensor_struct->psi_dot); + //graph_set_param_val(graph, ps->theta_dot, CONST_SET, sensor_struct->theta_dot); + //graph_set_param_val(graph, ps->phi_dot, CONST_SET, sensor_struct->phi_dot); + //graph_set_param_val(graph, ps->psi_dot, CONST_SET, sensor_struct->psi_dot); + graph_set_param_val(graph, ps->theta_dot, CONST_SET, sensor_struct->gyr_y); + graph_set_param_val(graph, ps->phi_dot, CONST_SET, sensor_struct->gyr_x); + graph_set_param_val(graph, ps->psi_dot, CONST_SET, sensor_struct->gyr_z); + // RC values graph_set_param_val(graph, ps->rc_pitch, CONST_SET, user_input_struct->pitch_angle_manual_setpoint); graph_set_param_val(graph, ps->rc_roll, CONST_SET, user_input_struct->roll_angle_manual_setpoint); diff --git a/quad/sw/modular_quad_pid/src/control_algorithm.h b/quad/src/quad_app/control_algorithm.h similarity index 100% rename from quad/sw/modular_quad_pid/src/control_algorithm.h rename to quad/src/quad_app/control_algorithm.h diff --git a/quad/sw/modular_quad_pid/src/controllers.c b/quad/src/quad_app/controllers.c similarity index 97% rename from quad/sw/modular_quad_pid/src/controllers.c rename to quad/src/quad_app/controllers.c index 7be7616e1a527ebb327c73609a8d93b84bf36508..1ebf713e3e101065e22086b816eca9454600160b 100644 --- a/quad/sw/modular_quad_pid/src/controllers.c +++ b/quad/src/quad_app/controllers.c @@ -12,8 +12,6 @@ #include "iic_utils.h" #include "quadposition.h" #include "util.h" -#include "uart.h" -#include "sleep.h" #include "stdio.h" #include <math.h> diff --git a/quad/sw/imu_logger/src/controllers.h b/quad/src/quad_app/controllers.h similarity index 100% rename from quad/sw/imu_logger/src/controllers.h rename to quad/src/quad_app/controllers.h diff --git a/quad/sw/imu_logger/src/conversion.c b/quad/src/quad_app/conversion.c similarity index 100% rename from quad/sw/imu_logger/src/conversion.c rename to quad/src/quad_app/conversion.c diff --git a/quad/sw/imu_logger/src/conversion.h b/quad/src/quad_app/conversion.h similarity index 100% rename from quad/sw/imu_logger/src/conversion.h rename to quad/src/quad_app/conversion.h diff --git a/quad/sw/modular_quad_pid/src/gam.h b/quad/src/quad_app/gam.h similarity index 95% rename from quad/sw/modular_quad_pid/src/gam.h rename to quad/src/quad_app/gam.h index 6c5ed85541558c33138ef1ee7c0d358126d39af3..0f4803e8d2a2cb50e6733acb278529ebb658f636 100644 --- a/quad/sw/modular_quad_pid/src/gam.h +++ b/quad/src/quad_app/gam.h @@ -1,8 +1,6 @@ #ifndef _GAM_H #define _GAM_H -#include "xbasic_types.h" - //Gyro, accelerometer, and magnetometer data structure //Used for reading an instance of the sensor data typedef struct { diff --git a/quad/src/quad_app/hw_iface.h b/quad/src/quad_app/hw_iface.h new file mode 100644 index 0000000000000000000000000000000000000000..bbd6bb6fc14171d0f506151a1b87bffb9b869b21 --- /dev/null +++ b/quad/src/quad_app/hw_iface.h @@ -0,0 +1,56 @@ +#ifndef HW_IFACE_H +#define HW_IFACE_H + +struct I2CDriver { + void *state; + int (*reset)(struct I2CDriver *self); + int (*write)(struct I2CDriver *self, + unsigned short device_addr, + unsigned char *data, + unsigned int length); + int (*read)(struct I2CDriver *self, + unsigned short device_addr, + unsigned char *buff, + unsigned int length); +}; + +struct PWMOutputDriver { + void *state; + int (*reset)(struct PWMOutputDriver *self); + int (*write)(struct PWMOutputDriver *self, unsigned int channel, unsigned long pulse_width_us); +}; + +struct PWMInputDriver { + void *state; + int (*reset)(struct PWMInputDriver *self); + int (*read)(struct PWMInputDriver *self, unsigned int channel, unsigned long *pulse_width_us); +}; + +struct UARTDriver { + void *state; + int (*reset)(struct UARTDriver *self); + int (*write)(struct UARTDriver *self, unsigned char c); + int (*read)(struct UARTDriver *self, unsigned char *c); +}; + +struct TimerDriver { + void *state; + int (*reset)(struct TimerDriver *self); + int (*restart)(struct TimerDriver *self); + int (*read)(struct TimerDriver *self, unsigned long long *us); +}; + +struct LEDDriver { + void *state; + int (*reset)(struct LEDDriver *self); + int (*turn_on)(struct LEDDriver *self); + int (*turn_off)(struct LEDDriver *self); +}; + +struct SystemDriver { + void *state; + int (*reset)(struct SystemDriver *self); + int (*sleep)(struct SystemDriver *self, unsigned long us); +}; + +#endif diff --git a/quad/src/quad_app/iic_utils.c b/quad/src/quad_app/iic_utils.c new file mode 100644 index 0000000000000000000000000000000000000000..90cdfb6872963b2c3ef5c7437a8abb9435e0c581 --- /dev/null +++ b/quad/src/quad_app/iic_utils.c @@ -0,0 +1,250 @@ +/** + * IIC_UTILS.c + * + * Utility functions for using I2C on a Diligent Zybo board. + * Supports the SparkFun MPU9150 and the LiDAR lite v2 sensor + */ + +#include <stdio.h> +#include <math.h> + +#include "iic_utils.h" + + +static struct I2CDriver *i2c; +static struct SystemDriver *sys; + +double magX_correction = -1, magY_correction, magZ_correction; + +void iic_set_globals(struct I2CDriver *given_i2c, struct SystemDriver *given_system) { + i2c = given_i2c; + sys = given_system; +} + +int iic0_mpu9150_start(){ + + // Device Reset & Wake up + iic0_mpu9150_write(0x6B, 0x80); + sys->sleep(sys, 5000); + + // 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 + + // Configure Gyro to 2000dps, Accel. to +/-8G + iic0_mpu9150_write(0x1B, 0x18); + iic0_mpu9150_write(0x1C, 0x10); + + // Enable I2C bypass for AUX I2C (Magnetometer) + iic0_mpu9150_write(0x37, 0x02); + + // Setup Mag + iic0_mpu9150_write(0x37, 0x02); //INT_PIN_CFG -- INT_LEVEL=0 ; INT_OPEN=0 ; LATCH_INT_EN=0 ; INT_RD_CLEAR=0 ; FSYNC_INT_LEVEL=0 ; FSYNC_INT_EN=0 ; I2C_BYPASS_EN=0 ; CLKOUT_EN=0 + + sys->sleep(sys, 100000); + + int i; + gam_t temp_gam; + + // Do about 20 reads to warm up the device + for(i=0; i < 20; ++i){ + if(iic0_mpu9150_read_gam(&temp_gam) == -1){ + return -1; + } + sys->sleep(sys, 1000); + } + + return 0; +} + +void iic0_mpu9150_stop(){ + + //Put MPU to sleep + iic0_mpu9150_write(0x6B, 0b01000000); +} + +void iic0_mpu9150_write(u8 register_addr, u8 data){ + + u16 device_addr = MPU9150_DEVICE_ADDR; + u8 buf[] = {register_addr, data}; + + // Check if within register range + if(register_addr < 0 || register_addr > 0x75){ + return; + } + + if(register_addr <= 0x12){ + device_addr = MPU9150_COMPASS_ADDR; + } + + i2c->write(i2c, device_addr, buf, 2); +} + +void iic0_mpu9150_read(u8* recv_buffer, u8 register_addr, int size){ + + u16 device_addr = MPU9150_DEVICE_ADDR; + u8 buf[] = {register_addr}; + + // Check if within register range + if(register_addr < 0 || register_addr > 0x75){ + } + + // Set device address to the if 0x00 <= register address <= 0x12 + if(register_addr <= 0x12){ + device_addr = MPU9150_COMPASS_ADDR; + } + + + i2c->write(i2c, device_addr, buf, 1); + i2c->read(i2c, device_addr, recv_buffer, size); +} + +void iic0_mpu9150_calc_mag_sensitivity(){ + + u8 buf[3]; + u8 ASAX, ASAY, ASAZ; + + // Quickly read from the factory ROM to get correction coefficents + iic0_mpu9150_write(0x0A, 0x0F); + sys->sleep(sys, 10000); + + // Read raw adjustment values + iic0_mpu9150_read(buf, 0x10,3); + ASAX = buf[0]; + ASAY = buf[1]; + ASAZ = buf[2]; + + // Set the correction coefficients + magX_correction = (ASAX-128)*0.5/128 + 1; + magY_correction = (ASAY-128)*0.5/128 + 1; + magZ_correction = (ASAZ-128)*0.5/128 + 1; +} + + +void iic0_mpu9150_read_mag(gam_t* gam){ + + u8 mag_data[6]; + i16 raw_magX, raw_magY, raw_magZ; + + // Grab calibrations if not done already + if(magX_correction == -1){ + iic0_mpu9150_calc_mag_sensitivity(); + } + + // Set Mag to single read mode + iic0_mpu9150_write(0x0A, 0x01); + sys->sleep(sys, 10000); + mag_data[0] = 0; + + // Keep checking if data is ready before reading new mag data + while(mag_data[0] == 0x00){ + iic0_mpu9150_read(mag_data, 0x02, 1); + } + + // Get mag data + iic0_mpu9150_read(mag_data, 0x03, 6); + + raw_magX = (mag_data[1] << 8) | mag_data[0]; + raw_magY = (mag_data[3] << 8) | mag_data[2]; + raw_magZ = (mag_data[5] << 8) | mag_data[4]; + + // Set magnetometer data to output + gam->mag_x = raw_magX * magX_correction; + gam->mag_y = raw_magY * magY_correction; + gam->mag_z = raw_magZ * magZ_correction; + +} + +/** + * Get Gyro Accel Mag (GAM) information + */ +int iic0_mpu9150_read_gam(gam_t* gam) { + + i16 raw_accel_x, raw_accel_y, raw_accel_z; + i16 gyro_x, gyro_y, gyro_z; + + u8 sensor_data[ACCEL_GYRO_READ_SIZE] = {}; + + // We should only get mag_data ~10Hz + //Xint8 mag_data[6] = {}; + + //readHandler = iic0_read_bytes(sensor_data, ACCEL_GYRO_BASE_ADDR, ACCEL_GYRO_READ_SIZE); + iic0_mpu9150_read(sensor_data, ACCEL_GYRO_BASE_ADDR, ACCEL_GYRO_READ_SIZE); + + //Calculate accelerometer data + raw_accel_x = sensor_data[ACC_X_H] << 8 | sensor_data[ACC_X_L]; + raw_accel_y = sensor_data[ACC_Y_H] << 8 | sensor_data[ACC_Y_L]; + raw_accel_z = sensor_data[ACC_Z_H] << 8 | sensor_data[ACC_Z_L]; + + // put in G's + gam->accel_x = (raw_accel_x / 4096.0) + ACCEL_X_BIAS; // 4,096 is the gain per LSB of the measurement reading based on a configuration range of +-8g + 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; + gyro_y = (sensor_data[GYR_Y_H] << 8 | sensor_data[GYR_Y_L]);// * G_GAIN; + gyro_z = (sensor_data[GYR_Z_H] << 8 | sensor_data[GYR_Z_L]);// * G_GAIN; + + //Get the number of degrees + //javey: converted to radians to following SI units + gam->gyro_xVel_p = ((gyro_x / GYRO_SENS) * DEG_TO_RAD) + GYRO_X_BIAS; + gam->gyro_yVel_q = ((gyro_y / GYRO_SENS) * DEG_TO_RAD) + GYRO_Y_BIAS; + gam->gyro_zVel_r = ((gyro_z / GYRO_SENS) * DEG_TO_RAD) + GYRO_Z_BIAS; + + return 0; +} + +////////////////////////////////////////////////// +// LIDAR +////////////////////////////////////////////////// + +int iic0_lidarlite_write(u8 register_addr, u8 data) { + u8 buf[] = {register_addr, data}; + + return i2c->write(i2c, LIDARLITE_DEVICE_ADDR, buf, 2); +} + +int iic0_lidarlite_read(u8* recv_buffer, u8 register_addr, int size) { + u8 buf[] = {register_addr}; + int status = 0; + + status |= i2c->write(i2c, LIDARLITE_DEVICE_ADDR, buf, 1); + status |= i2c->read(i2c, LIDARLITE_DEVICE_ADDR, recv_buffer, size); + return status; +} + +int iic0_lidarlite_init() { + int status = 0; + + // Device Reset & Wake up with default settings + status = iic0_lidarlite_write(0x00, 0x00); + sys->sleep(sys, 15000); + + // Enable Free Running Mode and distance measurements with correction + status |= iic0_lidarlite_write(0x11, 0xff); + status |= iic0_lidarlite_write(0x00, 0x04); + + return status; +} + +int iic0_lidarlite_sleep() { + return iic0_lidarlite_write(0x65, 0x84); +} + +int iic0_lidarlite_read_distance(lidar_t *lidar) { + u8 buf[2]; + int status = 0; + + // Read the sensor value + status = iic0_lidarlite_read(buf, 0x8f, 2); + lidar->distance_cm = buf[0] << 8 | buf[1]; + + return status; +} diff --git a/quad/sw/modular_quad_pid/src/iic_utils.h b/quad/src/quad_app/iic_utils.h similarity index 96% rename from quad/sw/modular_quad_pid/src/iic_utils.h rename to quad/src/quad_app/iic_utils.h index 8a8a9a3bbb37bccf40a44a80efe69719358377dd..b1ccb6861d9fdb779debe8e42f56b866573f97d2 100644 --- a/quad/sw/modular_quad_pid/src/iic_utils.h +++ b/quad/src/quad_app/iic_utils.h @@ -14,10 +14,8 @@ #ifndef IIC_UTILS_H #define IIC_UTILS_H - -#include "xbasic_types.h" -#include "xiicps.h" #include "type_def.h" +#include "hw_iface.h" // System configuration registers // (Please see Appendix B: System Level Control Registers in the Zybo TRM) @@ -48,9 +46,6 @@ #define WRITE_INTR_MASK (ARB_LOST | TIME_OUT | RX_OVF | TX_OVF | NACK) #define READ_INTR_MASK (ARB_LOST | TIME_OUT | RX_OVF | RX_UNF | NACK) -// Initialize hardware; Call this FIRST before calling any other functions -int iic0_init(); - /////////////////////////////////////////////////////////////////////////////// // MPU9150 Sensor Defines (Address is defined on the Sparkfun MPU9150 Datasheet) /////////////////////////////////////////////////////////////////////////////// @@ -101,6 +96,8 @@ int iic0_init(); #define ACCEL_Y_BIAS 0.009f #define ACCEL_Z_BIAS 0.087f +void iic_set_globals(struct I2CDriver *given_i2c, struct SystemDriver *given_system); + void iic0_mpu9150_write(u8 register_addr, u8 data); void iic0_mpu9150_read(u8* recv_buffer, u8 register_addr, int size); diff --git a/quad/src/quad_app/initialize_components.c b/quad/src/quad_app/initialize_components.c new file mode 100644 index 0000000000000000000000000000000000000000..858c0e9ffb80525c72c04726698a98eac45b518f --- /dev/null +++ b/quad/src/quad_app/initialize_components.c @@ -0,0 +1,96 @@ +/* + * initialize_components.c + * + * Created on: Feb 20, 2016 + * Author: ucart + */ + +#include "initialize_components.h" +#include "communication.h" +#include "sensor.h" +#include "iic_utils.h" + +//#define BENCH_TEST + +extern int Xil_AssertWait; + +int protection_loops(modular_structs_t *structs) +{ + u32 rc_commands[6]; // 6 "receiver_input" elements: Throttle, Pitch, Roll, Yaw, Gear, and Flap + + struct PWMInputDriver *pwm_inputs = &structs->hardware_struct.pwm_inputs; + read_rec_all(pwm_inputs, rc_commands); + + // wait for RC receiver to connect to transmitter + while(rc_commands[THROTTLE] < 75000) + read_rec_all(pwm_inputs, rc_commands); + + // wait until throttle is low and the gear switch is engaged (so you don't immediately break out of the main loop below) + // also wait for the flight mode to be set to manual + while(rc_commands[THROTTLE] > 125000 || read_kill(rc_commands[GEAR]) || !read_flap(rc_commands[FLAP])) { + process_received(structs); + read_rec_all(pwm_inputs, rc_commands); + } + + // let the pilot/observers know that the quad is now active + MIO7_led_on(); + + return 0; +} + +int init_structs(modular_structs_t *structs) { + struct LEDDriver *mio7_led = &structs->hardware_struct.mio7_led; + struct SystemDriver *sys = &structs->hardware_struct.sys; + if (mio7_led->reset(mio7_led)) return -1; + mio7_init_globals(mio7_led, sys); + // Turn off LED 7 to let observers know that the quad is not yet active + + mio7_led->turn_off(mio7_led); + + // Initialize the controller + control_algorithm_init(&structs->parameter_struct); + + // Initialize the logging + initialize_logging(&structs->log_struct, &structs->parameter_struct); + + // Initialize loop timers + struct TimerDriver *global_timer = &structs->hardware_struct.global_timer; + struct TimerDriver *axi_timer = &structs->hardware_struct.axi_timer; + if (global_timer->reset(global_timer)) { + return -1; + } + if (axi_timer->reset(axi_timer)) { + return -1; + } + timer_init_globals(global_timer, axi_timer); + + // Initialize UART0 + struct UARTDriver *uart = &structs->hardware_struct.uart; + if (uart->reset(uart)) { + return -1; + } + + // Initialize I2C controller + struct I2CDriver *i2c = &structs->hardware_struct.i2c; + if (i2c->reset(i2c)) { + return -1; + } + iic_set_globals(i2c, sys); + + // Initialize PWM Recorders and Motor outputs + struct PWMInputDriver *pwm_inputs = &structs->hardware_struct.pwm_inputs; + if (pwm_inputs->reset(pwm_inputs)) return -1; + struct PWMOutputDriver *pwm_outputs = &structs->hardware_struct.pwm_outputs; + if (pwm_outputs->reset(pwm_outputs)) return -1; + + // Initialize sensors + + //manual flight mode + structs->user_defined_struct.flight_mode = MANUAL_FLIGHT_MODE; + + // Get the first loop data from accelerometer for the gyroscope to use + if(sensor_init(&structs->raw_sensor_struct, &structs->sensor_struct) == -1) + return -1; + + return 0; +} diff --git a/quad/sw/modular_quad_pid/src/initialize_components.h b/quad/src/quad_app/initialize_components.h similarity index 64% rename from quad/sw/modular_quad_pid/src/initialize_components.h rename to quad/src/quad_app/initialize_components.h index 151f68296bd554a5d7f47b93691801090c6106ea..e1737abd83be3fd793adf8e60ff8b7aa1f84b10e 100644 --- a/quad/sw/modular_quad_pid/src/initialize_components.h +++ b/quad/src/quad_app/initialize_components.h @@ -10,11 +10,11 @@ #include "timer.h" #include "control_algorithm.h" -#include "platform.h" -#include "uart.h" #include "iic_utils.h" #include "util.h" +#include "type_def.h" #include "controllers.h" +#include "mio7_led.h" /** * @brief @@ -35,9 +35,7 @@ int protection_loops(modular_structs_t *structs); * error message * */ -int initializeAllComponents(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); +int init_structs(modular_structs_t *structs); #endif /* INITALIZE_COMPONENTS_H_ */ diff --git a/quad/src/quad_app/log_data.c b/quad/src/quad_app/log_data.c new file mode 100644 index 0000000000000000000000000000000000000000..d7a361dfe69963339efd502e89cf697446bfe5eb --- /dev/null +++ b/quad/src/quad_app/log_data.c @@ -0,0 +1,247 @@ +/* + * log_data.c + * + * Created on: Feb 20, 2016 + * Author: ucart + */ + +#include <stdio.h> +#include <stdlib.h> +#include <string.h> +#include <stdarg.h> +#include "PID.h" +#include "type_def.h" +#include "log_data.h" +#include "communication.h" +#include "computation_graph.h" +#include "node_pid.h" +#include "node_constant.h" +#include "node_mixer.h" + +// Current index of the log array +int arrayIndex = 0; +// Size of the array +int arraySize = 0; + +struct graph_tuple { // Tuple for + int block_id; + int sub_id; +}; + +// Holds a statically allocated string, as well as info about its size and capacity +// Used by safe_sprintf_cat +struct str { + char* str; + size_t size; + size_t capacity; +}; + + + /** + * Forward declarations + */ + void format_log(int idx, log_t* log_struct, struct str* buf); + +struct graph_tuple log_outputs[MAX_LOG_NUM]; +struct graph_tuple log_params[MAX_LOG_NUM]; +size_t n_outputs; +size_t n_params; + +float* logArray = NULL; +int row_size; + +static char units_output_str[512] = {}; +static char units_param_str[512] = {}; +static struct str units_output = { .str = units_output_str, .size = 0, .capacity = sizeof(units_output_str)}; +static struct str units_param = { .str = units_param_str, .size = 0, .capacity = sizeof(units_output_str)}; + +/* + * Does an sprintf and concatenation. Used just like sprintf, but pass in a pointer to a struct str instead. + * Returns the number of bytes that would have been written (just like snprintf) + * Will not write more than is available in the given string +*/ +int safe_sprintf_cat(struct str *str, const char *fmt, ...) { + size_t available = str->capacity - str->size; + va_list args; + va_start(args, fmt); + // Print to offset not more than remaining capacity characters + size_t full_size = vsnprintf(str->str + str->size, available, fmt, args); + va_end(args); + if (full_size >= available) { // Check for truncation + str->size = str->capacity; + } else { + str->size = str->size + full_size; + } + return full_size; +} + +void addOutputToLog(log_t* log_struct, int controller_id, int output_id, char* units) { + if (n_outputs < MAX_LOG_NUM) { + log_outputs[n_outputs].block_id = controller_id; + log_outputs[n_outputs].sub_id = output_id; + n_outputs++; + safe_sprintf_cat(&units_output, "\t%s", units); + } +} +void addParamToLog(log_t* log_struct, int controller_id, int param_id, char* units) { + if (n_params < MAX_LOG_NUM) { + log_params[n_params].block_id = controller_id; + log_params[n_params].sub_id = param_id; + n_params++; + safe_sprintf_cat(&units_param, "\t%s", units); + } +} + +void initialize_logging(log_t* log_struct, parameter_t* ps) { + char* rad = "rad"; + char* rad_s = "rad/s"; + char* pwm_val = "10ns_dutycycle"; + char* m = "m"; + 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); + addOutputToLog(log_struct, ps->pitch_pid, PID_CORRECTION, rad_s); + addOutputToLog(log_struct, ps->roll_pid, PID_CORRECTION, rad_s); + addOutputToLog(log_struct, ps->yaw_pid, PID_CORRECTION, rad_s); + 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->cur_roll, CONST_VAL, rad); + addOutputToLog(log_struct, ps->cur_yaw, CONST_VAL, rad); + addOutputToLog(log_struct, ps->vrpn_x, CONST_VAL, m); + addOutputToLog(log_struct, ps->vrpn_y, CONST_VAL, m); + addOutputToLog(log_struct, ps->vrpn_alt, CONST_VAL, m); + addOutputToLog(log_struct, ps->vrpn_pitch, CONST_VAL, rad); + addOutputToLog(log_struct, ps->vrpn_roll, CONST_VAL, rad); + 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); + + // TODO: Make this not stupid. Adding 6 for IMU and 1 for timestamp + row_size = n_outputs + n_params + 6 + 1; + size_t needed_memory = sizeof(float) * row_size * LOG_STARTING_SIZE; + logArray = malloc(needed_memory); + if (!logArray) { // malloc failed + arraySize = 0; + } else { + arraySize = LOG_STARTING_SIZE; + } +} + + +int log_data(log_t* log_struct, parameter_t* ps) +{ + if(arrayIndex >= arraySize) + { + return 1; + } + float* thisRow = &logArray[arrayIndex * row_size * sizeof(float)]; + int offset = 0; + thisRow[offset++] = log_struct->time_stamp; + thisRow[offset++] = log_struct->gam.accel_x; + thisRow[offset++] = log_struct->gam.accel_y; + thisRow[offset++] = log_struct->gam.accel_z; + thisRow[offset++] = log_struct->gam.gyro_xVel_p; + thisRow[offset++] = log_struct->gam.gyro_yVel_q; + thisRow[offset++] = log_struct->gam.gyro_zVel_r; + + int i; + for (i = 0; i < n_params; i++) { + thisRow[offset++] = graph_get_param_val(ps->graph, log_params[i].block_id, log_params[i].sub_id); + } + for (i = 0; i < n_outputs; i++) { + thisRow[offset++] = graph_get_output(ps->graph, log_outputs[i].block_id, log_outputs[i].sub_id); + } + + arrayIndex++; + return 0; +} + + +/** + * Prints all the log information. + * + * TODO: This should probably be transmitting in binary instead of ascii + */ + +void printLogging(hardware_t *hardware_struct, log_t* log_struct, parameter_t* ps){ + if (arrayIndex == 0) { + // Don't send any logs if nothing was logged + return; + } + char buf_arr[2560] = {}; + struct str buf = {.str = buf_arr, .size = 0, .capacity = sizeof(buf_arr)}; + + // Let user know that allocation failed + if (arraySize != LOG_STARTING_SIZE) { + safe_sprintf_cat(&buf, "Failed to allocate enough log memory\n"); + send_data(&hardware_struct->uart, LOG_ID, 0, buf.str, buf.size); + return; + } + // Comment header + safe_sprintf_cat(&buf, "# MicroCART On-board Quad Log\n# Sample size: %d\n", arrayIndex); + // Header names for the pre-defined values + 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; + const char* output_name = ps->graph->nodes[log_params[i].block_id].type->param_names[log_params[i].sub_id]; + safe_sprintf_cat(&buf, "\t%s_%s", block_name, output_name); + } + // Print all the recorded block outputs + for (i = 0; i < n_outputs; i++) { + const char* block_name = ps->graph->nodes[log_outputs[i].block_id].name; + const char* param_name = ps->graph->nodes[log_outputs[i].block_id].type->output_names[log_outputs[i].sub_id]; + safe_sprintf_cat(&buf, "\t%s_%s", block_name, param_name); + } + safe_sprintf_cat(&buf, "\n"); + + // Send header names + send_data(&hardware_struct->uart, LOG_ID, 0, buf.str, buf.size); + + // Send units header + buf.size = 0; + safe_sprintf_cat(&buf, "s\tG\tG\tG\trad/s\trad/s\trad/s"); // The pre-defined ones + safe_sprintf_cat(&buf, units_output.str); + safe_sprintf_cat(&buf, units_param.str); + safe_sprintf_cat(&buf, "\n"); + send_data(&hardware_struct->uart, LOG_ID, 0, buf.str, buf.size); + + /*************************/ + /* print & send log data */ + for(i = 0; i < arrayIndex; i++){ + format_log(i, log_struct, &buf); + send_data(&hardware_struct->uart, LOG_ID, 0, buf.str, buf.size); + } + + // Empty message of type LOG_END to indicate end of log + send_data(&hardware_struct->uart, LOG_END_ID, 0, buf.str, 0); +} + +void resetLogging() { + arrayIndex = 0; +} + +/* + * Fills the given buffer as ASCII for the recorded index, and returns the length of the string created +*/ +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)];\ + + safe_sprintf_cat(buf, "%f", row[0]); + for (i = 1; i < row_size; i++) { + safe_sprintf_cat(buf, "\t%f", row[i]); + } + safe_sprintf_cat(buf, "\n"); +} diff --git a/quad/sw/modular_quad_pid/src/log_data.h b/quad/src/quad_app/log_data.h similarity index 82% rename from quad/sw/modular_quad_pid/src/log_data.h rename to quad/src/quad_app/log_data.h index bb3622c931f7b56420175ea872420a39c7e904d7..34f1658d02f316918547bc0eedd760bcbf121264 100644 --- a/quad/sw/modular_quad_pid/src/log_data.h +++ b/quad/src/quad_app/log_data.h @@ -18,12 +18,12 @@ void initialize_logging(log_t* log_struct, parameter_t* ps); /** * Adds the given block output to the data to be logged */ -void addOutputToLog(log_t* log_struct, int controller_id, int output_id); +void addOutputToLog(log_t* log_struct, int controller_id, int output_id, char* units); /** * Adds the given block parameter to the data to be logged */ -void addParamToLog(log_t* log_struct, int controller_id, int param_id); +void addParamToLog(log_t* log_struct, int controller_id, int param_id, char* units); /** @@ -47,11 +47,12 @@ void addParamToLog(log_t* log_struct, int controller_id, int param_id); /** * Prints all the log information. */ - void printLogging(log_t* log_struct, parameter_t* ps); + void printLogging(hardware_t *hardware_struct, log_t* log_struct, parameter_t* ps); /** - * Fills the given buffer as ASCII for the recorded index, and returns the length of the string created + * Resets and clears logged data */ - int format_log(int idx, log_t* log_struct, char* buf); + void resetLogging(); + #endif /* LOG_DATA_H_ */ diff --git a/quad/sw/imu_logger/src/lscript.ld b/quad/src/quad_app/lscript.ld similarity index 100% rename from quad/sw/imu_logger/src/lscript.ld rename to quad/src/quad_app/lscript.ld diff --git a/quad/src/quad_app/mio7_led.c b/quad/src/quad_app/mio7_led.c new file mode 100644 index 0000000000000000000000000000000000000000..cabe67ad7b364557b48afa79adaf08f60b7b0c9a --- /dev/null +++ b/quad/src/quad_app/mio7_led.c @@ -0,0 +1,35 @@ +/* + * mio7_led.c + * + * Created on: Feb 20, 2016 + * Author: Amy Seibert + */ + +#include "mio7_led.h" + +struct LEDDriver *mio7_led; +struct SystemDriver *sys; + +void mio7_init_globals(struct LEDDriver *given_mio7_led, struct SystemDriver *given_system) { + mio7_led = given_mio7_led; + sys = given_system; +} + +void flash_MIO_7_led(int how_many_times, int ms_between_flashes) +{ + int i; + for (i = 0; i < how_many_times; i += 1) { + mio7_led->turn_on(mio7_led); + sys->sleep(sys, ms_between_flashes * 500); + mio7_led->turn_off(mio7_led); + sys->sleep(sys, ms_between_flashes * 500); + } +} + + +void MIO7_led_on() { + mio7_led->turn_on(mio7_led); +} +void MIO7_led_off() { + mio7_led->turn_off(mio7_led); +} diff --git a/quad/sw/modular_quad_pid/src/mio7_led.h b/quad/src/quad_app/mio7_led.h similarity index 79% rename from quad/sw/modular_quad_pid/src/mio7_led.h rename to quad/src/quad_app/mio7_led.h index 2517f6241e7442f361bb41ba1f456979edb6e8a0..6244e2c1157cff657170783303506a8303ff07f5 100644 --- a/quad/sw/modular_quad_pid/src/mio7_led.h +++ b/quad/src/quad_app/mio7_led.h @@ -9,8 +9,7 @@ #define MIO7_LED_H_ #include <stdio.h> -#include <xgpiops.h> -#include "sleep.h" +#include "hw_iface.h" /** * @brief @@ -25,18 +24,9 @@ */ void flash_MIO_7_led(int how_many_times, int ms_between_flashes); -/** - * @brief - * Turns off MIO7 LED. - * - */ +void mio7_init_globals(struct LEDDriver *given_mio7_led, struct SystemDriver *sys); +void MIO7_led_on(); void MIO7_led_off(); -/** - * @brief - * Turns on MIO7 LED. - * - */ -void MIO7_led_on(); #endif /* MIO7_LED_H_ */ diff --git a/quad/sw/imu_logger/src/new_PID.h b/quad/src/quad_app/new_PID.h similarity index 100% rename from quad/sw/imu_logger/src/new_PID.h rename to quad/src/quad_app/new_PID.h diff --git a/quad/sw/imu_logger/src/new_log_data.c b/quad/src/quad_app/new_log_data.c similarity index 100% rename from quad/sw/imu_logger/src/new_log_data.c rename to quad/src/quad_app/new_log_data.c diff --git a/quad/sw/modular_quad_pid/src/new_log_data.h b/quad/src/quad_app/new_log_data.h similarity index 97% rename from quad/sw/modular_quad_pid/src/new_log_data.h rename to quad/src/quad_app/new_log_data.h index 932eb1a9207f5372fac04658e85cfbe9b7359ddd..13e713a9ecd1ea71fd799de4860d36808bc2f856 100644 --- a/quad/sw/modular_quad_pid/src/new_log_data.h +++ b/quad/src/quad_app/new_log_data.h @@ -13,7 +13,6 @@ #include <string.h> #include "PID.h" #include "type_def.h" -#include "uart.h" #include "sleep.h" #include "communication.h" diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_bounds.c b/quad/src/quad_app/node_bounds.c similarity index 100% rename from quad/sw/modular_quad_pid/src/graph_blocks/node_bounds.c rename to quad/src/quad_app/node_bounds.c diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_bounds.h b/quad/src/quad_app/node_bounds.h similarity index 92% rename from quad/sw/modular_quad_pid/src/graph_blocks/node_bounds.h rename to quad/src/quad_app/node_bounds.h index 516ebc28ac065508e77296c0c2942ab35e9249fb..4c3b93256106bce8560daf28c67f19844fb2ea8f 100644 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_bounds.h +++ b/quad/src/quad_app/node_bounds.h @@ -1,6 +1,6 @@ #ifndef __NODE_BOUNDS_H__ #define __NODE_BOUNDS_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_bounds(struct computation_graph *graph, const char* name); diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_mixer.c b/quad/src/quad_app/node_mixer.c similarity index 95% rename from quad/sw/modular_quad_pid/src/graph_blocks/node_mixer.c rename to quad/src/quad_app/node_mixer.c index 8b702b360654b3e957d19743abc24b433f58f64d..316c1ce8218b835ee002c8c4352c97af111b318d 100644 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_mixer.c +++ b/quad/src/quad_app/node_mixer.c @@ -25,7 +25,7 @@ static void reset_mixer(void *state) {} static const char* const in_names[4] = {"Throttle", "Pitch", "Roll", "Yaw"}; static const char* const out_names[4] = {"PWM 0", "PWM 1", "PWM 2", "PWM 3"}; -static const char* const param_names[0] = {}; +static const char* const param_names[1] = {"You shouldnt see this"}; const struct graph_node_type node_mixer_type = { .input_names = in_names, .output_names = out_names, diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_mixer.h b/quad/src/quad_app/node_mixer.h similarity index 92% rename from quad/sw/modular_quad_pid/src/graph_blocks/node_mixer.h rename to quad/src/quad_app/node_mixer.h index 1d58cf54d0531725b8ad2c99195dd23fecbe713f..ba1ec1c4901db366610506f18e41f9883a41980b 100644 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_mixer.h +++ b/quad/src/quad_app/node_mixer.h @@ -1,6 +1,6 @@ #ifndef __NODE_MIXER_H__ #define __NODE_MIXER_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_mixer(struct computation_graph *graph, const char* name); diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_pid.c b/quad/src/quad_app/node_pid.c similarity index 84% rename from quad/sw/modular_quad_pid/src/graph_blocks/node_pid.c rename to quad/src/quad_app/node_pid.c index acf77b5b4051c446067dfaea395a05cf89d1f916..7222094577d6c4ba1f41c93f65e5bdbe00c4dc75 100644 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_pid.c +++ b/quad/src/quad_app/node_pid.c @@ -8,6 +8,7 @@ static double FLT_EPSILON = 0.0001; struct pid_node_state { double prev_error; // Previous error double acc_error; // Accumulated error + double last_filtered; // Last output from the filtered derivative }; // The generic PID diagram. This function takes in pid inputs (CUR_POINT and SETOINT) and calculates the output "pid_correction" @@ -49,13 +50,20 @@ static void pid_computation(void *state, const double* params, const double *inp pid_state->acc_error += error; } - double change_in_error = error - pid_state->prev_error; // Compute each term's contribution P = params[PID_KP] * error; I = params[PID_KI] * pid_state->acc_error * inputs[PID_DT]; - D = params[PID_KD] * (change_in_error / inputs[PID_DT]); - + // Low-pass filter on derivative + double change_in_error = error - pid_state->prev_error; + double term1 = params[PID_ALPHA] * pid_state->last_filtered; + double derivative = change_in_error / 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 outputs[PID_CORRECTION] = P + I + D; // Store the computed correction @@ -67,19 +75,20 @@ 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; } static const char* const in_names[3] = {"Cur point", "Setpoint", "dt"}; static const char* const out_names[1] = {"Correction"}; -static const char* const param_names[3] = {"Kp", "Ki", "Kd"}; +static const char* const param_names[4] = {"Kp", "Ki", "Kd", "alpha"}; const struct graph_node_type node_pid_type = { .input_names = in_names, .output_names = out_names, .param_names = param_names, .n_inputs = 3, .n_outputs = 1, - .n_params = 3, + .n_params = 4, .execute = pid_computation, .reset = reset_pid }; diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_pid.h b/quad/src/quad_app/node_pid.h similarity index 80% rename from quad/sw/modular_quad_pid/src/graph_blocks/node_pid.h rename to quad/src/quad_app/node_pid.h index 75ded4af02edbc2cacbc68035f5a0970d65e38dc..7b384bb1a233785877fc2cc79d56a8e2dd88aa10 100644 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_pid.h +++ b/quad/src/quad_app/node_pid.h @@ -1,6 +1,6 @@ #ifndef __NODE_PID_H__ #define __NODE_PID_H__ -#include "../computation_graph.h" +#include "computation_graph.h" int graph_add_node_pid(struct computation_graph *graph, const char* name); @@ -19,7 +19,8 @@ enum graph_node_pid_outputs { enum graph_node_pid_params { PID_KP, // Proportional constant PID_KI, // Integral constant - PID_KD // Derivative constant + PID_KD, // Derivative constant + PID_ALPHA // alpha = (1 - N*T_s); High values mean more filtering }; #endif // __NODE_PID_H__ diff --git a/quad/sw/modular_quad_pid/src/old_log_data.h b/quad/src/quad_app/old_log_data.h similarity index 97% rename from quad/sw/modular_quad_pid/src/old_log_data.h rename to quad/src/quad_app/old_log_data.h index 932eb1a9207f5372fac04658e85cfbe9b7359ddd..13e713a9ecd1ea71fd799de4860d36808bc2f856 100644 --- a/quad/sw/modular_quad_pid/src/old_log_data.h +++ b/quad/src/quad_app/old_log_data.h @@ -13,7 +13,6 @@ #include <string.h> #include "PID.h" #include "type_def.h" -#include "uart.h" #include "sleep.h" #include "communication.h" diff --git a/quad/sw/modular_quad_pid/src/packet_processing.c b/quad/src/quad_app/packet_processing.c similarity index 96% rename from quad/sw/modular_quad_pid/src/packet_processing.c rename to quad/src/quad_app/packet_processing.c index c6764a00b08771b9f8b995a48b80509289307c86..8652c92335a2c778569e6e9e5a98591e155ba626 100644 --- a/quad/sw/modular_quad_pid/src/packet_processing.c +++ b/quad/src/quad_app/packet_processing.c @@ -5,9 +5,7 @@ * Author: ucart */ #include "packet_processing.h" -#include "uart.h" #include "type_def.h" -#include "sleep.h" #include "util.h" #include "communication.h" diff --git a/quad/sw/imu_logger/src/packet_processing.h b/quad/src/quad_app/packet_processing.h similarity index 100% rename from quad/sw/imu_logger/src/packet_processing.h rename to quad/src/quad_app/packet_processing.h diff --git a/quad/sw/modular_quad_pid/src/main.c b/quad/src/quad_app/quad_app.c similarity index 52% rename from quad/sw/modular_quad_pid/src/main.c rename to quad/src/quad_app/quad_app.c index 64d82b3a997b1619226249b20c626453398659dd..22829b5c8d2a6e5247a670f348c4ecad03dc6473 100644 --- a/quad/sw/modular_quad_pid/src/main.c +++ b/quad/src/quad_app/quad_app.c @@ -15,22 +15,24 @@ #include "actuator_command_processing.h" #include "send_actuator_commands.h" #include "update_gui.h" +#include "communication.h" +#include "mio7_led.h" //#define BENCH_TEST //#define UART_BENCHMARK -int main() +int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)) { // Structures to be used throughout modular_structs_t structs = { }; + // Wire up hardware + setup_hardware(&structs.hardware_struct); // Initialize all required components and structs: // Uart, PWM receiver/generator, I2C, Sensor Board // Xilinx Platform, Loop Timer, Control Algorithm - int init_error = initializeAllComponents(&(structs.user_input_struct), &(structs.log_struct), - &(structs.raw_sensor_struct), &(structs.sensor_struct), &(structs.setpoint_struct), &(structs.parameter_struct), - &(structs.user_defined_struct), &(structs.raw_actuator_struct), &(structs.actuator_command_struct)); + int init_error = init_structs(&(structs)); if (init_error != 0) { return -1; @@ -41,9 +43,13 @@ int main() protection_loops(&structs); #endif + int last_kill_condition = kill_condition(&(structs.user_input_struct)); + // Main control loop - do + while (1) { + int this_kill_condition = kill_condition(&(structs.user_input_struct)); + // Processing of loop timer at the beginning of the control loop timer_start_loop(); @@ -68,7 +74,7 @@ int main() #ifndef BENCH_TEST // Get the user input and put it into user_input_struct - get_user_input(&(structs.log_struct), &(structs.user_input_struct)); + get_user_input(&(structs.hardware_struct), &(structs.log_struct), &(structs.user_input_struct)); // Get data from the sensors and put it into raw_sensor_struct get_sensors(&(structs.log_struct), &(structs.user_input_struct), &(structs.raw_sensor_struct)); @@ -76,59 +82,61 @@ int main() // Process the sensor data and put it into sensor_struct sensor_processing(&(structs.log_struct), &(structs.user_input_struct), &(structs.raw_sensor_struct), &(structs.sensor_struct)); - // Run the control algorithm - control_algorithm(&(structs.log_struct), &(structs.user_input_struct), &(structs.sensor_struct), &(structs.setpoint_struct), - &(structs.parameter_struct), &(structs.user_defined_struct), &(structs.actuator_command_struct), &structs); - - // Process the commands going to the actuators - //actuator_command_processing(&(structs.log_struct), &(structs.user_input_struct), &(structs.raw_actuator_struct), &(structs.actuator_command_struct)); - - // send the actuator commands - send_actuator_commands(&(structs.log_struct), &(structs.actuator_command_struct)); + if (!this_kill_condition) { + // Run the control algorithm + control_algorithm(&(structs.log_struct), &(structs.user_input_struct), &(structs.sensor_struct), &(structs.setpoint_struct), + &(structs.parameter_struct), &(structs.user_defined_struct), &(structs.actuator_command_struct), &structs); + // send the actuator commands + send_actuator_commands(&(structs.hardware_struct.pwm_outputs), &(structs.log_struct), &(structs.actuator_command_struct)); + } + else { + kill_motors(&(structs.hardware_struct.pwm_outputs)); + } // 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(structs.user_defined_struct.flight_mode == AUTO_FLIGHT_MODE) - { - // Log the data collected in this loop - log_data(&(structs.log_struct), &(structs.parameter_struct)); + if (!this_kill_condition) { + 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++; + static int loop_counter = 0; + loop_counter++; - // toggle the MIO7 on and off to show that the quad is in AUTO_FLIGHT_MODE - if(loop_counter == 10) - { - MIO7_led_off(); - } - else if(loop_counter >= 20) - { + // toggle the MIO7 on and off to show that the quad is in AUTO_FLIGHT_MODE + if(loop_counter == 10) + { + MIO7_led_off(); + } + else if(loop_counter >= 20) + { + + MIO7_led_on(); + loop_counter = 0; + } + } + if(structs.user_defined_struct.flight_mode == MANUAL_FLIGHT_MODE) { MIO7_led_on(); - loop_counter = 0; } - } - if(structs.user_defined_struct.flight_mode == MANUAL_FLIGHT_MODE) - MIO7_led_on(); - } while( -#ifndef BENCH_TEST - !kill_condition(&(structs.user_input_struct)) -#else - 1 -#endif - ); - - pwm_kill(); + if (this_kill_condition == 1 && last_kill_condition == 0) { + // Just disabled + printLogging(&structs.hardware_struct, &(structs.log_struct), &(structs.parameter_struct)); + resetLogging(); + MIO7_led_off(); + } - MIO7_led_off(); + last_kill_condition = this_kill_condition; + } - printLogging(&(structs.log_struct), &(structs.parameter_struct)); + kill_motors(&(structs.hardware_struct.pwm_outputs)); flash_MIO_7_led(10, 100); diff --git a/quad/src/quad_app/quad_app.h b/quad/src/quad_app/quad_app.h new file mode 100644 index 0000000000000000000000000000000000000000..85e753a1e14a5a87c91d36f2410651e4b696264c --- /dev/null +++ b/quad/src/quad_app/quad_app.h @@ -0,0 +1,8 @@ +#ifndef QUAD_APP_H +#define QUAD_APP_H + +#include "type_def.h" + +int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)); + +#endif diff --git a/quad/sw/imu_logger/src/quadposition.h b/quad/src/quad_app/quadposition.h similarity index 100% rename from quad/sw/imu_logger/src/quadposition.h rename to quad/src/quad_app/quadposition.h diff --git a/quad/src/quad_app/send_actuator_commands.c b/quad/src/quad_app/send_actuator_commands.c new file mode 100644 index 0000000000000000000000000000000000000000..c361e74db2146e44b80881fec18dde14efef44d3 --- /dev/null +++ b/quad/src/quad_app/send_actuator_commands.c @@ -0,0 +1,20 @@ +/* + * send_actuator_commands.c + * + * Created on: Feb 20, 2016 + * Author: ucart + */ + +#include "send_actuator_commands.h" +#include "util.h" + +int send_actuator_commands(struct PWMOutputDriver *pwm_outputs, log_t* log_struct, actuator_command_t* actuator_command_struct) { + int i; + // write the PWMs to the motors + + for (i = 0; i < 4; i++) { + pwm_outputs->write(pwm_outputs, i, actuator_command_struct->pwms[i]); + } + + return 0; +} diff --git a/quad/sw/modular_quad_pid/src/send_actuator_commands.h b/quad/src/quad_app/send_actuator_commands.h similarity index 80% rename from quad/sw/modular_quad_pid/src/send_actuator_commands.h rename to quad/src/quad_app/send_actuator_commands.h index ca337ad7b78546682c57776f3ac40f03d76c9d42..3f6fb0fc833e3dc87d291ca6a357eed115d17e94 100644 --- a/quad/sw/modular_quad_pid/src/send_actuator_commands.h +++ b/quad/src/quad_app/send_actuator_commands.h @@ -27,6 +27,6 @@ * error message * */ -int send_actuator_commands(log_t* log_struct, actuator_command_t* actuator_command_struct); +int send_actuator_commands(struct PWMOutputDriver *pwm_outputs, log_t* log_struct, actuator_command_t* actuator_command_struct); #endif /* SEND_ACTUATOR_COMMANDS_H_ */ diff --git a/quad/sw/modular_quad_pid/src/sensor.c b/quad/src/quad_app/sensor.c similarity index 100% rename from quad/sw/modular_quad_pid/src/sensor.c rename to quad/src/quad_app/sensor.c diff --git a/quad/sw/modular_quad_pid/src/sensor.h b/quad/src/quad_app/sensor.h similarity index 97% rename from quad/sw/modular_quad_pid/src/sensor.h rename to quad/src/quad_app/sensor.h index d9592b0ea5f5e1514307541590277ea4a1f8b07b..45791a5aa7830600b9750f73458bbd19fd066fd9 100644 --- a/quad/sw/modular_quad_pid/src/sensor.h +++ b/quad/src/quad_app/sensor.h @@ -14,7 +14,6 @@ #include "user_input.h" #include "iic_utils.h" #include "packet_processing.h" -#include "uart.h" /** * @brief diff --git a/quad/sw/modular_quad_pid/src/sensor_processing.c b/quad/src/quad_app/sensor_processing.c similarity index 95% rename from quad/sw/modular_quad_pid/src/sensor_processing.c rename to quad/src/quad_app/sensor_processing.c index 1a69d261624f692b55bf4dd6d295f40afe9ee425..d7bd7b707ac23b2b87e8c5aab8029840dce80b31 100644 --- a/quad/sw/modular_quad_pid/src/sensor_processing.c +++ b/quad/src/quad_app/sensor_processing.c @@ -79,6 +79,11 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se sensor_struct->psi_dot = (raw_sensor_struct->gam.gyro_yVel_q*sin_phi*sec_theta) + (raw_sensor_struct->gam.gyro_zVel_r*cos_phi*sec_theta); + // Copy in raw gyroscope values + sensor_struct->gyr_x = raw_sensor_struct->gam.gyro_xVel_p; + sensor_struct->gyr_y = raw_sensor_struct->gam.gyro_yVel_q; + 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; diff --git a/quad/sw/modular_quad_pid/src/sensor_processing.h b/quad/src/quad_app/sensor_processing.h similarity index 100% rename from quad/sw/modular_quad_pid/src/sensor_processing.h rename to quad/src/quad_app/sensor_processing.h diff --git a/quad/src/quad_app/test/test_quad_app.c b/quad/src/quad_app/test/test_quad_app.c new file mode 100644 index 0000000000000000000000000000000000000000..8c9a45deada50d444eeac0b5996ff285d8656984 --- /dev/null +++ b/quad/src/quad_app/test/test_quad_app.c @@ -0,0 +1,294 @@ +#include "communication.h" +#include <string.h> +#include "queue.h" +#include "test.h" + +struct Queue *queue; +struct UARTDriver *uart; + +int mock_uart_read(struct UARTDriver *self, unsigned char *c) { + return queue_remove(queue, c); +} + +struct UARTDriver * mock_uart_malloc() { + struct UARTDriver *uart = malloc(sizeof(struct UARTDriver)); + uart->read = mock_uart_read; + return uart; +} + +void queue_add_corruption(struct Queue *q, int num) { + int val = 0xAA; + int i; + for (i = 0; i < num; i += 1) { + val = (val << 1) ^ i; + if (val == 0xBE) queue_add(q, 0); + else queue_add(q, val); + } +} + +void queue_add_short(struct Queue *q, short val) { + queue_add(q, val & 0x00FF); + queue_add(q, val >> 8); +} + +// Return checksum +unsigned char queue_add_packet(struct Queue *q, + unsigned short type, + unsigned short id, + unsigned short length, + unsigned char *data) { + queue_add(q, 0xBE); + queue_add(q, type & 0x00FF); + queue_add(q, type >> 8); + queue_add(q, id & 0x00FF); + queue_add(q, id >> 8); + queue_add(q, length & 0x00FF); + queue_add(q, length >> 8); + + unsigned char checksum = 0; + checksum ^= 0xBE; + checksum ^= type & 0x00FF; + checksum ^= type >> 8; + checksum ^= id & 0x00FF; + checksum ^= id >> 8; + checksum ^= length & 0x00FF; + checksum ^= length >> 8; + int i; + for (i = 0; i < length; i += 1) { + queue_add(q, data[i]); + checksum ^= data[i]; + } + queue_add(q, checksum); + return checksum; +} + +// Spying into communication.c's global variables +extern u8 packet[MAX_PACKET_SIZE]; +extern int bytes_recv; +extern unsigned char packet_checksum; + +// Test fails when no BE and run out +int test_try_receive_packet_fails_when_no_BE_and_run_out() { + bytes_recv = 0; + uart = mock_uart_malloc(); + queue = queue_malloc(5); + queue_add(queue, 0); + queue_add(queue, 0); + queue_add(queue, 1); + + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 0); + + // Try again to verify that we actually ran out + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 0); + + return 0; +} + +// Test fails when no BE and too much (check resume) +int test_try_receive_packet_fails_when_no_BE_and_too_much() { + bytes_recv = 0; + uart = mock_uart_malloc(); + int size = 255; + queue = queue_malloc(size); + queue_add_corruption(queue, size); + + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 0); + + // Ensure that we quit trying + test_assert(size - queue_size(queue) <= MAX_PACKET_SIZE); + + return 0; +} + +// Test fails when BE and run out (check resume) +int test_try_receive_packet_fails_when_BE_and_run_out() { + bytes_recv = 0; + uart = mock_uart_malloc(); + queue = queue_malloc(100); + queue_add_corruption(queue, 10); + queue_add(queue, 0xBE); + + queue_add(queue, 1); + queue_add(queue, 2); + queue_add(queue, 3); + + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 4); + + test_assert(packet[0] == 0xBE); + test_assert(packet[1] == 1); + test_assert(packet[2] == 2); + test_assert(packet[3] == 3); + + // Try again to verify that we actually ran out + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 4); + + return 0; +} + +// Test fails when BE and nonsensical length (check resume) +int test_try_receive_packet_fails_when_BE_and_big_length() { + bytes_recv = 0; + uart = mock_uart_malloc(); + queue = queue_malloc(500); + int i; + queue_add_corruption(queue, 10); + queue_add(queue, 0xBE); + queue_add_short(queue, 0); + queue_add_short(queue, 0); + queue_add_short(queue, 500); + for (i = 0; i < 10; i += 1) queue_add_corruption(queue, i); + + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 0); + + // Try again to verify that we actually ran out + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 0); + + return 0; +} + +// Test fails when BE and length and run out (check resume) +int test_try_receive_packet_fails_when_BE_length_and_run_out() { + bytes_recv = 0; + uart = mock_uart_malloc(); + queue = queue_malloc(500); + int i; + queue_add_corruption(queue, 20); + queue_add(queue, 0xBE); + queue_add_short(queue, 0); + queue_add_short(queue, 0); + queue_add_short(queue, 4); + unsigned char data[4] = {1, 2, 3, 4}; + for (i = 0; i < 2; i += 1) queue_add(queue, data[i]); + + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 9); + test_assert(packet[0] == 0xBE); + test_assert(packet[1] == 0); + test_assert(packet[2] == 0); + test_assert(packet[3] == 0); + test_assert(packet[4] == 0); + test_assert(packet[5] == 4); + test_assert(packet[6] == 0); + test_assert(packet[7] == 1); + test_assert(packet[8] == 2); + + // Try again to verify that we actually ran out + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 9); + + return 0; +} + +// Test fails when BE and length and data and run out (check resume) +int test_try_receive_packet_fails_when_BE_length_data_and_run_out() { + bytes_recv = 0; + uart = mock_uart_malloc(); + queue = queue_malloc(500); + int i; + queue_add_corruption(queue, 10); + queue_add(queue, 0xBE); + queue_add_short(queue, 0); + queue_add_short(queue, 0); + queue_add_short(queue, 4); + unsigned char data[4] = {1, 2, 3, 4}; + for (i = 0; i < 4; i += 1) queue_add(queue, data[i]); + + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 11); + test_assert(packet[0] == 0xBE); + test_assert(packet[1] == 0); + test_assert(packet[2] == 0); + test_assert(packet[3] == 0); + test_assert(packet[4] == 0); + test_assert(packet[5] == 4); + test_assert(packet[6] == 0); + test_assert(packet[7] == 1); + test_assert(packet[8] == 2); + test_assert(packet[9] == 3); + test_assert(packet[10] == 4); + + // Try again to verify that we actually ran out + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 11); + + return 0; +} + +// Test fails when BE, length, data, and checksum fails +int test_try_receive_packet_fails_when_BE_length_data_and_bad_checksum() { + bytes_recv = 0; + uart = mock_uart_malloc(); + queue = queue_malloc(500); + int i; + queue_add_corruption(queue, 10); + queue_add(queue, 0xBE); + queue_add_short(queue, 0); + queue_add_short(queue, 0); + queue_add_short(queue, 4); + unsigned char data[4] = {1, 2, 3, 4}; + for (i = 0; i < 4; i += 1) queue_add(queue, data[i]); + queue_add(queue, 0xFF); // bad checksum + queue_add(queue, 0xBE); // next start + + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 1); + test_assert(packet[0] == 0xBE); + + // Try again to verify that we actually ran out + test_assert(try_receive_packet(uart)); + test_assert(bytes_recv == 1); + + return 0; +} + +// Test succeeds when BE, length, data, checksum +int test_try_receive_packet_succeeds() { + bytes_recv = 0; + uart = mock_uart_malloc(); + queue = queue_malloc(500); + int i; + queue_add_corruption(queue, 10);; + unsigned char data[4] = {1, 2, 3, 4}; + unsigned char checksum = queue_add_packet(queue, 0, 0, 4, data); + + int failure = try_receive_packet(uart); + test_assert(!failure); + test_assert(bytes_recv == 12); + test_assert(packet[0] == 0xBE); + test_assert(packet[1] == 0); + test_assert(packet[2] == 0); + test_assert(packet[3] == 0); + test_assert(packet[4] == 0); + test_assert(packet[5] == 4); + test_assert(packet[6] == 0); + test_assert(packet[7] == 1); + test_assert(packet[8] == 2); + test_assert(packet[9] == 3); + test_assert(packet[10] == 4); + test_assert(packet[11] == checksum); + + // Try again to verify that we don't lose the ready packet + test_assert(!try_receive_packet(uart)); + test_assert(bytes_recv == 12); + + return 0; +} + +int main() { + TEST(test_try_receive_packet_fails_when_no_BE_and_run_out); + TEST(test_try_receive_packet_fails_when_no_BE_and_too_much); + TEST(test_try_receive_packet_fails_when_BE_and_run_out); + TEST(test_try_receive_packet_fails_when_BE_and_big_length); + TEST(test_try_receive_packet_fails_when_BE_length_and_run_out); + TEST(test_try_receive_packet_fails_when_BE_length_data_and_run_out); + TEST(test_try_receive_packet_fails_when_BE_length_data_and_bad_checksum); + TEST(test_try_receive_packet_succeeds); + return test_summary(); +} diff --git a/quad/src/quad_app/timer.c b/quad/src/quad_app/timer.c new file mode 100644 index 0000000000000000000000000000000000000000..b7f68afbc3455758702f5f55a59623af987e1dc3 --- /dev/null +++ b/quad/src/quad_app/timer.c @@ -0,0 +1,54 @@ +#include "timer.h" + +u64 before = 0, after = 0; +float LOOP_TIME; // microseconds +float time_stamp = 0; + +struct TimerDriver *global_timer; +struct TimerDriver *axi_timer; + +void timer_init_globals(struct TimerDriver *given_global_timer, struct TimerDriver *given_axi_timer) { + global_timer = given_global_timer; + axi_timer = given_axi_timer; +} + +int timer_start_loop() +{ + //timing code + LOOP_TIME = ((float)(after - before)); + global_timer->read(global_timer, &before); + axi_timer->restart(axi_timer); + return 0; +} + +int timer_end_loop(log_t *log_struct) +{ + // get number of useconds its taken to run the loop thus far + u64 usec_loop; + axi_timer->read(axi_timer, &usec_loop); + + // attempt to make each loop run for the same amount of time + while(usec_loop < DESIRED_USEC_PER_LOOP) { + axi_timer->read(axi_timer, &usec_loop); + } + + //timing code + global_timer->read(global_timer, &after); + time_stamp += get_last_loop_time(); + + // Log the timing information + log_struct->time_stamp = time_stamp; + log_struct->time_slice = get_last_loop_time(); + + return 0; +} + +float get_last_loop_time() { + return (float)LOOP_TIME / 1000000; +} + +u32 timer_get_count() { + u64 time; + return axi_timer->read(axi_timer, &time); + return time; +} diff --git a/quad/sw/modular_quad_pid/src/timer.h b/quad/src/quad_app/timer.h similarity index 78% rename from quad/sw/modular_quad_pid/src/timer.h rename to quad/src/quad_app/timer.h index 5ebc293e8e679b4ea3e3a24a6d899352938efc40..8f3d12fb4930cf172c8747aaeaaf6a5f70a6491d 100644 --- a/quad/sw/modular_quad_pid/src/timer.h +++ b/quad/src/quad_app/timer.h @@ -13,18 +13,6 @@ // desired loop time is not guaranteed (its possible that the loop may take longer than desired) #define DESIRED_USEC_PER_LOOP 5000 // gives 5ms loops -#define PL_CLK_CNTS_PER_USEC 100 - -/** - * @brief - * Initializes the items necessary for loop timing. - * - * @return - * error message - * - */ -int timer_init(); - /** * @brief * Does processing of the loop timer at the beginning of the control loop. @@ -48,6 +36,7 @@ int timer_end_loop(log_t *log_struct); // Returns the number of seconds the last loop took float get_last_loop_time(); -uint32_t timer_get_count(); +u32 timer_get_count(); +void timer_init_globals(struct TimerDriver *global_timer, struct TimerDriver *axi_timer); #endif /* TIMER_H_ */ diff --git a/quad/sw/modular_quad_pid/src/type_def.h b/quad/src/quad_app/type_def.h similarity index 91% rename from quad/sw/modular_quad_pid/src/type_def.h rename to quad/src/quad_app/type_def.h index 40c0db97f613724b0fa92fef886bc359b0c9bd7f..8d6363cfa70c9eeff3bb0aa8dbac7cafefd466a1 100644 --- a/quad/sw/modular_quad_pid/src/type_def.h +++ b/quad/src/quad_app/type_def.h @@ -11,6 +11,15 @@ #include <stdint.h> #include "commands.h" #include "computation_graph.h" +#include "hw_iface.h" + +typedef unsigned char u8; +typedef unsigned short u16; +typedef unsigned long u32; +typedef unsigned long long u64; +typedef signed char i8; +typedef signed short i16; +typedef signed long i32; /** * @brief @@ -140,7 +149,7 @@ typedef struct PID_values{ * */ typedef struct user_input_t { - int rc_commands[6]; // Commands from the RC transmitter + u32 rc_commands[6]; // Commands from the RC transmitter // float cam_x_pos; // Current x position from the camera system @@ -254,13 +263,13 @@ typedef struct sensor { int acc_z_t; // time of accelerometer z data - int gyr_x; // gyroscope x data + float gyr_x; // gyroscope x data int gyr_x_t; // time of gyroscope x data - int gyr_y; // gyroscope y data + float gyr_y; // gyroscope y data int gyr_y_t; // time of gyroscope y data - int gyr_z; // gyroscope z data + float gyr_z; // gyroscope z data int gyr_z_t; // time of gyroscope z data int ldr_z; //lidar z data (altitude) @@ -371,6 +380,30 @@ typedef struct actuator_command_t { int pwms[4]; } actuator_command_t; +enum PWMChannels { + MOTOR_0, + MOTOR_1, + MOTOR_2, + MOTOR_3, + RC_INPUT_0, + RC_INPUT_1, + RC_INPUT_2, + RC_INPUT_3, + RC_INPUT_4, + RC_INPUT_5, +}; + +typedef struct hardware_t { + struct I2CDriver i2c; + struct PWMInputDriver pwm_inputs; + struct PWMOutputDriver pwm_outputs; + struct UARTDriver uart; + struct TimerDriver global_timer; + struct TimerDriver axi_timer; + struct LEDDriver mio7_led; + struct SystemDriver sys; +} hardware_t; + /** * @brief * Structures to be used throughout @@ -385,6 +418,7 @@ typedef struct modular_structs { user_defined_t user_defined_struct; raw_actuator_t raw_actuator_struct; actuator_command_t actuator_command_struct; + hardware_t hardware_struct; } modular_structs_t; //////// END MAIN MODULAR STRUCTS diff --git a/quad/sw/imu_logger/src/update_gui.c b/quad/src/quad_app/update_gui.c similarity index 100% rename from quad/sw/imu_logger/src/update_gui.c rename to quad/src/quad_app/update_gui.c diff --git a/quad/sw/imu_logger/src/update_gui.h b/quad/src/quad_app/update_gui.h similarity index 100% rename from quad/sw/imu_logger/src/update_gui.h rename to quad/src/quad_app/update_gui.h diff --git a/quad/sw/modular_quad_pid/src/user_input.c b/quad/src/quad_app/user_input.c similarity index 56% rename from quad/sw/modular_quad_pid/src/user_input.c rename to quad/src/quad_app/user_input.c index b3b4331e200aad0dfc88c87684e7d28b06def909..bcb7478bf3ce6b7d9b5e6457e82bdafdce02d915 100644 --- a/quad/sw/modular_quad_pid/src/user_input.c +++ b/quad/src/quad_app/user_input.c @@ -6,27 +6,26 @@ */ #include "user_input.h" -#include "uart.h" -#include "controllers.h" -int get_user_input(log_t* log_struct, user_input_t* user_input_struct) +int get_user_input(hardware_t *hardware_struct, log_t* log_struct, user_input_t* user_input_struct) { - // Read in values from RC Receiver - read_rec_all(user_input_struct->rc_commands); + // Read in values from RC Receiver + struct PWMInputDriver *pwm_inputs = &hardware_struct->pwm_inputs; + read_rec_all(pwm_inputs, user_input_struct->rc_commands); - //create setpoints for manual flight - // currently in units of radians - user_input_struct->yaw_manual_setpoint = convert_from_receiver_cmd(user_input_struct->rc_commands[YAW], YAW_MAX, YAW_CENTER, YAW_MIN, YAW_RAD_TARGET, -(YAW_RAD_TARGET)); - user_input_struct->roll_angle_manual_setpoint = convert_from_receiver_cmd(user_input_struct->rc_commands[ROLL], ROLL_MAX, ROLL_CENTER, ROLL_MIN, ROLL_RAD_TARGET, -(ROLL_RAD_TARGET)); - user_input_struct->pitch_angle_manual_setpoint = convert_from_receiver_cmd(user_input_struct->rc_commands[PITCH], PITCH_MAX, PITCH_CENTER, PITCH_MIN, PITCH_RAD_TARGET, -(PITCH_RAD_TARGET)); + //create setpoints for manual flight + // currently in units of radians + user_input_struct->yaw_manual_setpoint = convert_from_receiver_cmd(user_input_struct->rc_commands[YAW], YAW_MAX, YAW_CENTER, YAW_MIN, YAW_RAD_TARGET, -(YAW_RAD_TARGET)); + user_input_struct->roll_angle_manual_setpoint = convert_from_receiver_cmd(user_input_struct->rc_commands[ROLL], ROLL_MAX, ROLL_CENTER, ROLL_MIN, ROLL_RAD_TARGET, -(ROLL_RAD_TARGET)); + user_input_struct->pitch_angle_manual_setpoint = convert_from_receiver_cmd(user_input_struct->rc_commands[PITCH], PITCH_MAX, PITCH_CENTER, PITCH_MIN, PITCH_RAD_TARGET, -(PITCH_RAD_TARGET)); - // Listen on bluetooth and if there's a packet, - // then receive the packet and set hasPacket for later processing - // "update packet" type processing is done in sensor.c - // "command packet" type processing is done in control_algorithm.c - //user_input_struct->hasPacket = tryReceivePacket(user_input_struct->sb, 0); + // Listen on bluetooth and if there's a packet, + // then receive the packet and set hasPacket for later processing + // "update packet" type processing is done in sensor.c + // "command packet" type processing is done in control_algorithm.c + //user_input_struct->hasPacket = tryReceivePacket(user_input_struct->sb, 0); - return 0; + return 0; } int kill_condition(user_input_t* user_input_struct) diff --git a/quad/sw/modular_quad_pid/src/user_input.h b/quad/src/quad_app/user_input.h similarity index 95% rename from quad/sw/modular_quad_pid/src/user_input.h rename to quad/src/quad_app/user_input.h index c17fe91fedaca0b1437dbba8913fa9a3e9da774a..c289e99c96e437dcfed2398a6711bcf9ecadb786 100644 --- a/quad/sw/modular_quad_pid/src/user_input.h +++ b/quad/src/quad_app/user_input.h @@ -79,7 +79,7 @@ * error message * */ -int get_user_input(log_t* log_struct, user_input_t* user_input_struct); +int get_user_input(hardware_t *hardware_struct, log_t* log_struct, user_input_t* user_input_struct); int kill_condition(user_input_t* user_input_struct); float convert_from_receiver_cmd(int receiver_cmd, int max_receiver_cmd, int center_receiver_cmd, int min_receiver_cmd, float max_target, float min_target); diff --git a/quad/src/quad_app/util.c b/quad/src/quad_app/util.c new file mode 100644 index 0000000000000000000000000000000000000000..25a8dae95cce20ef69fd5d3e71302269aac1b513 --- /dev/null +++ b/quad/src/quad_app/util.c @@ -0,0 +1,95 @@ +#include "util.h" + +#include <stdlib.h> +#include <stdio.h> +#include <string.h> +#include <math.h> +#include "PID.h" +#include "log_data.h" +#include "controllers.h" + +extern int motor0_bias, motor1_bias, motor2_bias, motor3_bias; + +/** + * Reads all 6 receiver channels at once + */ +void read_rec_all(struct PWMInputDriver *pwm_input, u32 *mixer){ + int i; + for(i = 0; i < 6; i++){ + pwm_input->read(pwm_input, i, &mixer[i]); + } +} + +int hexStrToInt(char *buf, int startIdx, int endIdx) { + int result = 0; + int i; + int power = 0; + for (i=endIdx; i >= startIdx; i--) { + int value = buf[i]; + if ('0' <= value && value <= '9') { + value -= '0'; + } else if ('a' <= value && value <= 'f') { + value -= 'a'; + value += 10; + } else if ('A' <= value && value <= 'F') { + value -= 'A'; + value += 10; + } + + result += (2 << (4 * power)) * value; + power++; + } + + return result; +} + +/** + * Argument is the reading from the pwm_recorder4 which is connected to the gear pwm + * If the message from the receiver is 0 - gear, kill the system by sending a 1 + * Otherwise, do nothing + */ +int read_kill(int gear){ + if(gear > 115000 && gear < 125000) + return 1; + return 0; +} + +int read_flap(int flap) +{ + // flap '0' is 108,000 CC (Up) + // flap '1' is 192,000 CC (Down) + // here we say if the reading is greater than 150,000 than its '1'; '0' otherwise + if(flap > 150000) + return 1; + return 0; +} + +/** + * 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); +} + +int build_int(u8 *buff) { + return buff[3] << 24 + | buff[2] << 16 + | buff[1] << 8 + | buff[0]; +} + +float build_float(u8 *buff) { + union { + float f; + int i; + } x; + + x.i = buff[3] << 24 + | buff[2] << 16 + | buff[1] << 8 + | buff[0]; + return x.f; +} diff --git a/quad/src/quad_app/util.h b/quad/src/quad_app/util.h new file mode 100644 index 0000000000000000000000000000000000000000..0d06e5fe0075b5c0808a2bca4e8746e57ecf7dcf --- /dev/null +++ b/quad/src/quad_app/util.h @@ -0,0 +1,22 @@ +#ifndef _UTIL_H +#define _UTIL_H + +#include "type_def.h" +#include <stdlib.h> +#include <stdio.h> +#include <string.h> +#include <math.h> +#include "PID.h" +#include "log_data.h" +#include "controllers.h" +#include "hw_iface.h" + +void read_rec_all(struct PWMInputDriver *pwm_input, u32 *mixer); +int read_kill(int gear); +int read_flap(int flap); +void kill_motors(struct PWMOutputDriver *pwm_outputs); + +int build_int(u8 *buff); +float build_float(u8 *buff); + +#endif //_UTIL_H diff --git a/quad/src/queue/.gitignore b/quad/src/queue/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..da2dc67a4f0e61a89b67664a64a475efc2adca6d --- /dev/null +++ b/quad/src/queue/.gitignore @@ -0,0 +1,3 @@ +run_tests +obj/ +obj-zybo/ diff --git a/quad/src/queue/Makefile b/quad/src/queue/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..b1121285df3bd56474ce02b2be03b0d03fbb7900 --- /dev/null +++ b/quad/src/queue/Makefile @@ -0,0 +1,6 @@ +TOP=../.. + +NAME = queue +REQLIBS = -ltest + +include $(TOP)/library.mk diff --git a/quad/src/queue/queue.c b/quad/src/queue/queue.c new file mode 100644 index 0000000000000000000000000000000000000000..243975b0a3f14a77e811ecb33249528ff98ba5c4 --- /dev/null +++ b/quad/src/queue/queue.c @@ -0,0 +1,68 @@ +#include "queue.h" + +int queue_init(struct Queue *q, volatile unsigned char *buff, unsigned int max_size) { + q->buff = buff; + q->max_size = max_size + 1; + q->start = max_size; + q->end = 0; + return 0; +} + +struct Queue * queue_malloc(unsigned int max_size) { + unsigned char *buff = malloc(sizeof(unsigned char) * (max_size + 1)); + if (buff == NULL) return NULL; + struct Queue *q = malloc(sizeof(struct Queue)); + if (q == NULL) return NULL; + queue_init(q, buff, max_size); + return q; +} + +void queue_free(struct Queue *q) { + free((unsigned char *) q->buff); + free(q); +} + +int queue_add(struct Queue *q, unsigned char c) { + if (queue_full(q)) { + return -1; + } + q->buff[q->end] = c; + q->end += 1; + q->end %= q->max_size; + return 0; +} + +int queue_remove(struct Queue *q, unsigned char *c) { + if (queue_empty(q)) { + return -1; + } + q->start += 1; + q->start %= q->max_size; + *c = q->buff[q->start]; + return 0; +} + +int queue_size(struct Queue *q) { + return (q->max_size + q->end - q->start - 1) % q->max_size; +} + +int queue_full(struct Queue *q) { + return q->start == q->end;; +} + +int queue_empty(struct Queue *q) { + return queue_size(q) == 0; +} + +void queue_print(struct Queue *q) { + int i; + printf("buffer: (size: %d, full: %d, empty: %d)\n", queue_size(q), queue_full(q), queue_empty(q)); + for (i = 0; i < q->max_size; i += 1) { + char c = (char) q->buff[i]; + if (c == 0) c = '-'; + printf("%c", c);; + if (i == q->start) printf(" <- start"); + if (i == q->end) printf(" <- end"); + printf("\n"); + } +} diff --git a/quad/src/queue/queue.h b/quad/src/queue/queue.h new file mode 100644 index 0000000000000000000000000000000000000000..1adf670ba24877b93087aba40470057bfcc766e8 --- /dev/null +++ b/quad/src/queue/queue.h @@ -0,0 +1,25 @@ +#ifndef QUEUE_H +#define QUEUE_H + +#include <stdlib.h> +#include <stdio.h> + +struct Queue { + volatile unsigned char *buff; + unsigned int max_size; + unsigned int start; + unsigned int end; +}; + + +int queue_init(struct Queue *q, volatile unsigned char *buff, unsigned int max_size); +struct Queue * queue_malloc(unsigned int max_size); +void queue_free(struct Queue *q); +int queue_add(struct Queue *q, unsigned char c); +int queue_remove(struct Queue *q, unsigned char *c); +int queue_size(struct Queue *q); +int queue_full(struct Queue *q); +int queue_empty(struct Queue *q); +void queue_print(struct Queue *q); + +#endif diff --git a/quad/src/queue/test/test_queue.c b/quad/src/queue/test/test_queue.c new file mode 100644 index 0000000000000000000000000000000000000000..02328d1f90994daa884c28cea06db4c63cca0d9a --- /dev/null +++ b/quad/src/queue/test/test_queue.c @@ -0,0 +1,170 @@ +#include "test.h" +#include "queue.h" + +int test_free() { + struct Queue *q = queue_malloc(4); + queue_free(q); + return 0; +} + +int test_add() { + struct Queue *q = queue_malloc(4); + unsigned char c; + test_assert(!queue_add(q, 'a')); + test_assert(!queue_add(q, 'b')); + test_assert(!queue_add(q, 'c')); + test_assert(!queue_add(q, 'd')); + test_assert(queue_add(q, 'x')); + queue_print(q); + + queue_remove(q, &c); + queue_remove(q, &c); + test_assert(!queue_add(q, 'e')); + test_assert(!queue_add(q, 'f')); + test_assert(queue_add(q, 'x')); + queue_print(q); + + return 0; +} + +int test_remove() { + int failed = 0; + struct Queue *q = queue_malloc(4); + unsigned char c; + queue_add(q, 'x'); + queue_add(q, 'x'); + test_assert(!queue_remove(q, &c)); + test_assert((c == 'x')); + test_assert(!queue_remove(q, &c)); + test_assert((c == 'x')); + test_assert(queue_remove(q, &c)); + queue_print(q); + + queue_add(q, 'a'); + queue_add(q, 'b'); + queue_add(q, 'c'); + queue_add(q, 'd'); + queue_add(q, 'x'); + test_assert(!queue_remove(q, &c)); + test_assert((c == 'a')); + test_assert(!queue_remove(q, &c)); + test_assert((c == 'b')); + test_assert(!queue_remove(q, &c)); + test_assert((c == 'c')); + test_assert(!queue_remove(q, &c)); + test_assert((c == 'd')); + test_assert(queue_remove(q, &c)); + + return failed; +} + + +int test_size() { + int failed = 0; + struct Queue *q = queue_malloc(4); + unsigned char c; + + test_assert(queue_size(q) == 0); + queue_print(q); + + queue_add(q, 'a'); + test_assert(queue_size(q) == 1); + queue_print(q); + + queue_add(q, 'b'); + test_assert(queue_size(q) == 2); + queue_print(q); + + queue_add(q, 'c'); + test_assert(queue_size(q) == 3); + queue_print(q); + + queue_add(q, 'd'); + test_assert(queue_size(q) == 4); + queue_print(q); + + queue_remove(q, &c); + queue_remove(q, &c); + test_assert(queue_size(q) == 2); + queue_print(q); + + queue_add(q, 'e'); + test_assert(queue_size(q) == 3); + queue_print(q); + + return failed; +} + +int test_full() { + int failed = 0; + struct Queue *q = queue_malloc(4); + unsigned char c; + + test_assert(!queue_full(q)); + queue_print(q); + + queue_add(q, 'a'); + queue_add(q, 'b'); + queue_add(q, 'c'); + test_assert(!queue_full(q)); + queue_print(q); + + queue_add(q, 'd'); + test_assert(queue_full(q)); + queue_print(q); + + queue_remove(q, &c); + test_assert(!queue_full(q)); + queue_print(q); + + queue_remove(q, &c); + queue_add(q, 'x'); + queue_add(q, 'x'); + test_assert(queue_full(q)); + queue_print(q); + + return failed; +} + +int test_empty() { + int failed = 0; + struct Queue *q = queue_malloc(4); + unsigned char c; + + test_assert(queue_empty(q)); + queue_print(q); + + queue_add(q, 'a'); + queue_add(q, 'b'); + queue_add(q, 'c'); + test_assert(!queue_empty(q)); + queue_print(q); + + queue_add(q, 'd'); + test_assert(!queue_empty(q)); + queue_print(q); + + queue_remove(q, &c); + test_assert(!queue_empty(q)); + queue_print(q); + + queue_remove(q, &c); + queue_remove(q, &c); + test_assert(!queue_empty(q)); + + queue_remove(q, &c); + test_assert(queue_empty(q)); + + return failed; +} + + +int main() { + test(test_free, "test_free"); + test(test_add, "test_add"); + test(test_remove, "test_remove"); + test(test_size, "test_size"); + test(test_full, "test_full"); + test(test_empty, "test_empty"); + return test_summary(); +} diff --git a/quad/src/test/.gitignore b/quad/src/test/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..da2dc67a4f0e61a89b67664a64a475efc2adca6d --- /dev/null +++ b/quad/src/test/.gitignore @@ -0,0 +1,3 @@ +run_tests +obj/ +obj-zybo/ diff --git a/quad/src/test/Makefile b/quad/src/test/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..2156f7994add62a9f65f41b3b33ffc852097de5d --- /dev/null +++ b/quad/src/test/Makefile @@ -0,0 +1,6 @@ +TOP=../.. + +NAME = test +REQLIBS = -ltest + +include $(TOP)/library.mk diff --git a/quad/lib/test/README.md b/quad/src/test/README.md similarity index 100% rename from quad/lib/test/README.md rename to quad/src/test/README.md diff --git a/quad/lib/test/example.c b/quad/src/test/example/example.c similarity index 100% rename from quad/lib/test/example.c rename to quad/src/test/example/example.c diff --git a/quad/lib/test/test.c b/quad/src/test/test.c similarity index 73% rename from quad/lib/test/test.c rename to quad/src/test/test.c index dc2ef00efc660656444a502f5e802873e4aee80e..98863ecd8f23ad713677726f2c866f7223f81585 100644 --- a/quad/lib/test/test.c +++ b/quad/src/test/test.c @@ -1,8 +1,9 @@ #include "test.h" static int num_tests = 0; -static struct Test tests[128]; +static struct Test tests[255]; static int longest_test_name = 0; +static int num_assertions = 0; void test(int (*function)(), char *test_name) { int test_name_length = strlen(test_name); @@ -13,6 +14,8 @@ void test(int (*function)(), char *test_name) { pid_t pid = fork(); if (pid == 0) { // test process + puts("----------------------------------------"); + printf("#%3d: %s\n", num_tests + 1, test_name); int exit_status = function(); exit(exit_status); } else { @@ -40,10 +43,18 @@ void test(int (*function)(), char *test_name) { } } +void test_assert(int success) { + num_assertions += 1; + if (!success) { + printf("FAILED assertion #%d\n", num_assertions); + exit(1); + } +} + int test_summary() { unsigned char at_least_one_test_failed = 0; int num_failed = 0; - puts("---------------------------------"); + puts("--------------------------------------------------------------------------------"); puts("Test results:"); puts(""); int i = 0; @@ -54,7 +65,7 @@ int test_summary() { } puts(""); printf("Total: %3d of %-3d tests passed\n", num_tests - num_failed, num_tests); - puts("---------------------------------"); + puts("--------------------------------------------------------------------------------"); num_tests = 0; longest_test_name = 0; return at_least_one_test_failed; diff --git a/quad/lib/test/test.h b/quad/src/test/test.h similarity index 68% rename from quad/lib/test/test.h rename to quad/src/test/test.h index 862769fc347187b3b7e6b408dab7b501d8388015..ac50248ece65f20b0060e5ae7f5509a38a8fb821 100644 --- a/quad/lib/test/test.h +++ b/quad/src/test/test.h @@ -7,13 +7,16 @@ #include <sys/types.h> #include <sys/wait.h> +#define TEST(name) test(name, #name) + struct Test { - char name[64]; - char result_msg[32]; + char name[255]; + char result_msg[255]; unsigned char failed; }; void test(int (*)(), char *); +void test_assert(int success); int test_summary(); #endif diff --git a/quad/sw/.gitignore b/quad/sw/.gitignore deleted file mode 100644 index 97d34666eb7e6ae5008b1a6eec4fc9a13839611b..0000000000000000000000000000000000000000 --- a/quad/sw/.gitignore +++ /dev/null @@ -1,5 +0,0 @@ -SDK.log -test.log -.metadata/ -system_bsp/ - diff --git a/quad/sw/modular_quad_pid/.build_app.tcl b/quad/sw/modular_quad_pid/.build_app.tcl deleted file mode 100644 index ae51135bb7ea13e1f14bc28fda3da7f2c4751181..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/.build_app.tcl +++ /dev/null @@ -1,3 +0,0 @@ -cd .. -sdk set_workspace . -sdk build_project -type app -name modular_quad_pid diff --git a/quad/sw/modular_quad_pid/.build_bsp.tcl b/quad/sw/modular_quad_pid/.build_bsp.tcl deleted file mode 100644 index 6188f060ae618549d958ff723b7fc645778128c6..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/.build_bsp.tcl +++ /dev/null @@ -1,3 +0,0 @@ -cd .. -sdk set_workspace . -sdk build_project -type bsp -name system_bsp diff --git a/quad/sw/modular_quad_pid/.create_bsp.tcl b/quad/sw/modular_quad_pid/.create_bsp.tcl deleted file mode 100644 index 48668ef358b00c6a12098269411fe91a613053a1..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/.create_bsp.tcl +++ /dev/null @@ -1,3 +0,0 @@ -cd .. -sdk set_workspace . -sdk create_bsp_project -name system_bsp -hwproject system_hw_platform -proc ps7_cortexa9_0 -os standalone diff --git a/quad/sw/modular_quad_pid/.gitignore b/quad/sw/modular_quad_pid/.gitignore deleted file mode 100644 index e09df2b7841f50ade27e462a4a8c87ecd4b230f0..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -Debug/ -Release/ -bootimage/ diff --git a/quad/sw/modular_quad_pid/gen_diagram/gen_diagram b/quad/sw/modular_quad_pid/gen_diagram/gen_diagram deleted file mode 100755 index 67f69853389aab3b2ae03822ea66932ef2ef902e..0000000000000000000000000000000000000000 Binary files a/quad/sw/modular_quad_pid/gen_diagram/gen_diagram and /dev/null differ diff --git a/quad/sw/modular_quad_pid/gen_diagram/network.png b/quad/sw/modular_quad_pid/gen_diagram/network.png deleted file mode 100644 index 86e48ace55c7bf76f2b50525988701848631e327..0000000000000000000000000000000000000000 Binary files a/quad/sw/modular_quad_pid/gen_diagram/network.png and /dev/null differ diff --git a/quad/sw/modular_quad_pid/src/commands.c b/quad/sw/modular_quad_pid/src/commands.c deleted file mode 120000 index e03a0ea45faafddf983aed9e6bb2eae3b2902ac3..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/commands.c +++ /dev/null @@ -1 +0,0 @@ -../../../../groundStation/src/backend/commands.c \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/commands.h b/quad/sw/modular_quad_pid/src/commands.h deleted file mode 120000 index b0ff517e5fdb2363f2afda70b29e57aee9fdc663..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/commands.h +++ /dev/null @@ -1 +0,0 @@ -../../../../groundStation/src/backend/commands.h \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/communication.c b/quad/sw/modular_quad_pid/src/communication.c deleted file mode 100644 index bba31571e0e5e6b26bf244f538d3719021d2b7d8..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/communication.c +++ /dev/null @@ -1,210 +0,0 @@ -#include "communication.h" -#include "uart_buff.h" - -#define INTC XScuGic -#define COMM_UART_DEVICE_ID XPAR_PS7_UART_0_DEVICE_ID -#define COMM_INTC_DEVICE_ID XPAR_SCUGIC_SINGLE_DEVICE_ID -#define COMM_UART_INT_IRQ_ID XPAR_PS7_UART_0_INTR//XPAR_XUARTPS_0_INTR - -#define BAUD_RATE 921600 -// Maximum number of bytes to be received within our loop time, -// plus the maximum packet size that might be carried over from the last call, -// plus 128 for a little buffer -// (bit/s) * (seconds) / (10 bits / byte for UART) -#define MAX_PACKET_SIZE 256 -#define UART_BUF_SIZE (((BAUD_RATE * (DESIRED_USEC_PER_LOOP / 1000) / 1000) / 10) + MAX_PACKET_SIZE + 128) - -//#define INTERRUPT_BENCHMARK - -// Declaration of interrupt handler -void Handler(void *CallBackRef, u32 Event, unsigned int EventData); - -// Pointer to the UART driver instance -static XUartPs* uartInstPtr; - - -int initUartComms() { - uartInstPtr = uart0_init(COMM_UART_DEVICE_ID, BAUD_RATE); - // Initialize UART0 (Bluetooth/WiFi) - if(!uartInstPtr) { - return -1; - } - - uart0_clearFIFOs(); - - if (uart0_int_init(COMM_UART_INT_IRQ_ID, (Xil_ExceptionHandler) uart_interrupt_handler) != XST_SUCCESS) { - return -1; - } - - - /* - * Setup the handlers for the UART that will be called from the - * interrupt context when data has been sent and received, specify - * a pointer to the UART driver instance as the callback reference - * so the handlers are able to access the instance data - */ - //XUartPs_SetHandler(uartInstPtr, (XUartPs_Handler)Handler, uartInstPtr); - - u32 IntrMask = XUARTPS_IXR_RXFULL | XUARTPS_IXR_RXOVR | XUARTPS_IXR_TOUT; - - XUartPs_SetInterruptMask(uartInstPtr, IntrMask); - - - /* - * Set the receiver timeout. If it is not set, and the last few bytes - * of data do not trigger the over-water or full interrupt, the bytes - * will not be received. By default it is disabled. - * Timeout duration = RecvTimeout x 4 x Bit Period. 0 disables the - * timeout function. - * - * The setting of 8 will timeout after 8 x 4 = 32 character times. - * Increase the time out value if baud rate is high, decrease it if - * baud rate is low. - */ - XUartPs_SetRecvTimeout(uartInstPtr, 8); - - // Second argument is the number of bytes to trigger an interrupt at - XUartPs_SetFifoThreshold(uartInstPtr, 48); - - return 0; -} - -int process_packet(modular_structs_t *structs) { - metadata_t meta_data; - // parse metadata - meta_data.begin_char = uart_buff_get_u8(0); - meta_data.msg_type = uart_buff_get_u16(1); - meta_data.msg_id = uart_buff_get_u16(3); - meta_data.data_len = uart_buff_get_u16(5); - unsigned char packet_checksum = uart_buff_get_u8(7+meta_data.data_len); - //unsigned char* packet_data = packet + sizeof(metadata_t); - - // Compute checksum - int i; - unsigned char calculated_checksum = 0; - for(i = 0; i < meta_data.data_len + 7; i++){ - calculated_checksum ^= uart_buff_get_u8(i); - } - // Discard if checksum didn't match - if(packet_checksum != calculated_checksum) { - uart_buff_consume_packet(); - return -1; - } - - // Call appropriate function for packet - (* (MessageTypes[meta_data.msg_type].functionPtr))(structs); - - uart_buff_consume_packet(); - - return 0; - -} - -/* - * Temporarily disables interrupts and returns the interrupt state, for restoring them - */ -u32 disable_interrupts() { - u32 ImrRegister; - ImrRegister = XUartPs_ReadReg(uartInstPtr->Config.BaseAddress, XUARTPS_IMR_OFFSET); - XUartPs_WriteReg(uartInstPtr->Config.BaseAddress, XUARTPS_IDR_OFFSET, XUARTPS_IXR_MASK); - return ImrRegister; -} - -/* - * Restores the interrupt state, saved from disable_interrupts - */ -void restore_interrupts(u32 intr_state) { - XUartPs_WriteReg(uartInstPtr->Config.BaseAddress, XUARTPS_IER_OFFSET, intr_state); -} - -void process_received(modular_structs_t *structs) { - // Parse as many packets as possible - while (uart_buff_packet_ready()) { - process_packet(structs); - } -} - -void uart_interrupt_handler(XUartPs *InstancePtr) { - u32 IsrStatus; - - /* - * Read the interrupt ID register to determine which - * interrupt is active - */ - IsrStatus = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, - XUARTPS_IMR_OFFSET); - - IsrStatus &= XUartPs_ReadReg(InstancePtr->Config.BaseAddress, - XUARTPS_ISR_OFFSET); - - /* - * Read the Channel Status Register to determine if there is any data in - * the RX FIFO - */ - - u32 CsrRegister = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, - XUARTPS_SR_OFFSET); - -#ifdef INTERRUPT_BENCHMARK - u32 start_time = timer_get_count(); -#endif - - while (0 == (CsrRegister & XUARTPS_SR_RXEMPTY) && !uart_buff_full()) { - u8 byte = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, XUARTPS_FIFO_OFFSET); - uart_buff_add_u8(byte); - CsrRegister = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, XUARTPS_SR_OFFSET); - } - -#ifdef INTERRUPT_BENCHMARK - u32 end_time = timer_get_count(); - u32 duration = end_time - start_time; - send_data(0, 0, 0, (char *) &duration, 8); -#endif - - // Clear the interrupt status. - XUartPs_WriteReg(InstancePtr->Config.BaseAddress, XUARTPS_ISR_OFFSET, - IsrStatus); -} - -int send_data(u16 type_id, u16 msg_id, char* data, size_t size) { - //---------------------------------------------------------------------------------------------- - // index|| 0 | 1 | 2 | 3 & 4 | 5 & 6 | 7+ | end | - //---------------------------------------------------------------------------------------------| - // msg param|| beg char | msg type | msg id | data len (bytes) | data | checksum | - //-------------------------------------------------------------------------------------------- | - // bytes|| 1 | 2 | 2 | 2 | var | 1 | - //---------------------------------------------------------------------------------------------- - - char formattedHeader[7]; - - // Begin Char: - formattedHeader[0] = BEGIN_CHAR; - // Msg type 2 bytes: - formattedHeader[1] = type_id & 0x000000ff; - formattedHeader[2] = (type_id >> 8) & 0x000000ff; - // Msg id 2 bytes - formattedHeader[3] = msg_id & 0x000000ff; - formattedHeader[4] = (msg_id >> 8) & 0x000000ff; - // Data length and data - bytes 5&6 for len, 7+ for data - formattedHeader[5] = size & 0x000000ff; - formattedHeader[6] = (size >> 8) & 0x000000ff; - - // Compute checksum while sending - unsigned char packet_checksum = 0; - - int i; - for(i = 0; i < 7; i++) { - packet_checksum ^= formattedHeader[i]; - uart0_sendByte(formattedHeader[i]); - } - // Send data - for (i = 0; i < size; i++) { - packet_checksum ^= data[i]; - uart0_sendByte(data[i]); - } - //uart0_sendBytes(data, size); - // Send checksum - uart0_sendByte(packet_checksum); - - return 0; -} diff --git a/quad/sw/modular_quad_pid/src/communication.h b/quad/sw/modular_quad_pid/src/communication.h deleted file mode 100644 index 92c7c86d039af0362e3d5a40c84187f6ad9fd29a..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/communication.h +++ /dev/null @@ -1,21 +0,0 @@ -#ifndef _COMMUNICATION_H -#define _COMMUNICATION_H - -#include <xuartps.h> -#include "xparameters.h" -#include "xscugic.h" -#include "xil_exception.h" - -#include "type_def.h" -#include "uart.h" -#include "mio7_led.h" -#include "timer.h" -#include "commands.h" -#include "uart_buff.h" - -int initUartComms(); -void process_received(modular_structs_t *structs); -void uart_interrupt_handler(XUartPs *InstancePtr); -int send_data(u16 type_id, u16 msg_id, char* data, size_t size); - -#endif diff --git a/quad/sw/modular_quad_pid/src/computation_graph.c b/quad/sw/modular_quad_pid/src/computation_graph.c deleted file mode 120000 index c9f4c52019cf7cf8763b84aa9954a943f37ba2a1..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/computation_graph.c +++ /dev/null @@ -1 +0,0 @@ -../../../computation_graph/src/computation_graph.c \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/computation_graph.h b/quad/sw/modular_quad_pid/src/computation_graph.h deleted file mode 120000 index eb8fe7bfea6e123f35220c668690d99d290daa72..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/computation_graph.h +++ /dev/null @@ -1 +0,0 @@ -../../../computation_graph/src/computation_graph.h \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_add.c b/quad/sw/modular_quad_pid/src/graph_blocks/node_add.c deleted file mode 120000 index d7025e0c28ea1028022b77e23924a7734ee55e00..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_add.c +++ /dev/null @@ -1 +0,0 @@ -../../../../computation_graph/src/graph_blocks/node_add.c \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_add.h b/quad/sw/modular_quad_pid/src/graph_blocks/node_add.h deleted file mode 120000 index 4f4b0ea11eb74e5c45426122afb754f13b098266..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_add.h +++ /dev/null @@ -1 +0,0 @@ -../../../../computation_graph/src/graph_blocks/node_add.h \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_constant.c b/quad/sw/modular_quad_pid/src/graph_blocks/node_constant.c deleted file mode 120000 index 5091326ebef1cc7c79bc07820f2069960704809d..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_constant.c +++ /dev/null @@ -1 +0,0 @@ -../../../../computation_graph/src/graph_blocks/node_constant.c \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/graph_blocks/node_constant.h b/quad/sw/modular_quad_pid/src/graph_blocks/node_constant.h deleted file mode 120000 index d751234bdd8d5b88435e8c5f49c35bc15e55bbf0..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/graph_blocks/node_constant.h +++ /dev/null @@ -1 +0,0 @@ -../../../../computation_graph/src/graph_blocks/node_constant.h \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/src/iic_utils.c b/quad/sw/modular_quad_pid/src/iic_utils.c deleted file mode 100644 index 290d5f9b60e5861d10d1e2770870fbc98e020b30..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/iic_utils.c +++ /dev/null @@ -1,458 +0,0 @@ -/** - * IIC_UTILS.c - * - * Utility functions for using I2C on a Diligent Zybo board. - * Supports the SparkFun MPU9150 and the LiDAR lite v2 sensor - */ - -#include <stdio.h> -#include <sleep.h> -#include <math.h> - -#include "xparameters.h" -#include "iic_utils.h" -#include "xbasic_types.h" -#include "xiicps.h" - -XIicPs_Config* i2c_config; -XIicPs I2C0; -double magX_correction = -1, magY_correction, magZ_correction; -int XIicPs_MasterSendPolled_ours(XIicPs *InstancePtr, u8 *MsgPtr, int ByteCount, u16 SlaveAddr); -int XIicPs_SetupMaster(XIicPs *InstancePtr, int Role); -s32 TransmitFifoFill(XIicPs *InstancePtr); - -int iic0_init(){ - - //Make sure CPU_1x clk is enabled for I2C controller - Xuint16* aper_ctrl = (Xuint16*) IO_CLK_CONTROL_REG_ADDR; - - if(*aper_ctrl & 0x00040000){ - xil_printf("CPU_1x is set to I2C0\r\n"); - } - - else{ - xil_printf("CPU_1x is not set to I2C0..Setting now\r\n"); - *aper_ctrl |= 0x00040000; - } - - - // Look up - i2c_config = XIicPs_LookupConfig(XPAR_PS7_I2C_0_DEVICE_ID); - - XStatus status = XIicPs_CfgInitialize(&I2C0, i2c_config, i2c_config->BaseAddress); - - // Check if initialization was successful - if(status != XST_SUCCESS){ - return -1; - } - - // Reset the controller and set the clock to 400kHz - XIicPs_Reset(&I2C0); - XIicPs_SetSClk(&I2C0, 400000); - - - return 0; -} - -int iic0_mpu9150_start(){ - - // Device Reset & Wake up - iic0_mpu9150_write(0x6B, 0x80); - usleep(5000); - - // 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 - - // Configure Gyro to 2000dps, Accel. to +/-8G - iic0_mpu9150_write(0x1B, 0x18); - iic0_mpu9150_write(0x1C, 0x10); - - // Enable I2C bypass for AUX I2C (Magnetometer) - iic0_mpu9150_write(0x37, 0x02); - - // Setup Mag - iic0_mpu9150_write(0x37, 0x02); //INT_PIN_CFG -- INT_LEVEL=0 ; INT_OPEN=0 ; LATCH_INT_EN=0 ; INT_RD_CLEAR=0 ; FSYNC_INT_LEVEL=0 ; FSYNC_INT_EN=0 ; I2C_BYPASS_EN=0 ; CLKOUT_EN=0 - - usleep(100000); - - int i; - gam_t temp_gam; - - // Do about 20 reads to warm up the device - for(i=0; i < 20; ++i){ - if(iic0_mpu9150_read_gam(&temp_gam) == -1){ - return -1; - } - usleep(1000); - } - - return 0; -} - -void iic0_mpu9150_stop(){ - - //Put MPU to sleep - iic0_mpu9150_write(0x6B, 0b01000000); -} - -void iic0_mpu9150_write(u8 register_addr, u8 data){ - - u16 device_addr = MPU9150_DEVICE_ADDR; - u8 buf[] = {register_addr, data}; - - // Check if within register range - if(register_addr < 0 || register_addr > 0x75){ - return; - } - - if(register_addr <= 0x12){ - device_addr = MPU9150_COMPASS_ADDR; - } - - XIicPs_MasterSendPolled_ours(&I2C0, buf, 2, device_addr); - -} - -void iic0_mpu9150_read(u8* recv_buffer, u8 register_addr, int size){ - - u16 device_addr = MPU9150_DEVICE_ADDR; - u8 buf[] = {register_addr}; - - // Check if within register range - if(register_addr < 0 || register_addr > 0x75){ - } - - // Set device address to the if 0x00 <= register address <= 0x12 - if(register_addr <= 0x12){ - device_addr = MPU9150_COMPASS_ADDR; - } - - - XIicPs_MasterSendPolled_ours(&I2C0, buf, 1, device_addr); - XIicPs_MasterRecvPolled(&I2C0, recv_buffer,size,device_addr); -} - -void iic0_mpu9150_calc_mag_sensitivity(){ - - u8 buf[3]; - u8 ASAX, ASAY, ASAZ; - - // Quickly read from the factory ROM to get correction coefficents - iic0_mpu9150_write(0x0A, 0x0F); - usleep(10000); - - // Read raw adjustment values - iic0_mpu9150_read(buf, 0x10,3); - ASAX = buf[0]; - ASAY = buf[1]; - ASAZ = buf[2]; - - // Set the correction coefficients - magX_correction = (ASAX-128)*0.5/128 + 1; - magY_correction = (ASAY-128)*0.5/128 + 1; - magZ_correction = (ASAZ-128)*0.5/128 + 1; -} - - -void iic0_mpu9150_read_mag(gam_t* gam){ - - u8 mag_data[6]; - Xint16 raw_magX, raw_magY, raw_magZ; - - // Grab calibrations if not done already - if(magX_correction == -1){ - iic0_mpu9150_calc_mag_sensitivity(); - } - - // Set Mag to single read mode - iic0_mpu9150_write(0x0A, 0x01); - usleep(10000); - mag_data[0] = 0; - - // Keep checking if data is ready before reading new mag data - while(mag_data[0] == 0x00){ - iic0_mpu9150_read(mag_data, 0x02, 1); - } - - // Get mag data - iic0_mpu9150_read(mag_data, 0x03, 6); - - raw_magX = (mag_data[1] << 8) | mag_data[0]; - raw_magY = (mag_data[3] << 8) | mag_data[2]; - raw_magZ = (mag_data[5] << 8) | mag_data[4]; - - // Set magnetometer data to output - gam->mag_x = raw_magX * magX_correction; - gam->mag_y = raw_magY * magY_correction; - gam->mag_z = raw_magZ * magZ_correction; - -} - -/** - * Get Gyro Accel Mag (GAM) information - */ -int iic0_mpu9150_read_gam(gam_t* gam) { - - Xint16 raw_accel_x, raw_accel_y, raw_accel_z; - Xint16 gyro_x, gyro_y, gyro_z; - - Xuint8 sensor_data[ACCEL_GYRO_READ_SIZE] = {}; - - // We should only get mag_data ~10Hz - //Xint8 mag_data[6] = {}; - - //readHandler = iic0_read_bytes(sensor_data, ACCEL_GYRO_BASE_ADDR, ACCEL_GYRO_READ_SIZE); - iic0_mpu9150_read(sensor_data, ACCEL_GYRO_BASE_ADDR, ACCEL_GYRO_READ_SIZE); - - //Calculate accelerometer data - raw_accel_x = sensor_data[ACC_X_H] << 8 | sensor_data[ACC_X_L]; - raw_accel_y = sensor_data[ACC_Y_H] << 8 | sensor_data[ACC_Y_L]; - raw_accel_z = sensor_data[ACC_Z_H] << 8 | sensor_data[ACC_Z_L]; - - // put in G's - gam->accel_x = (raw_accel_x / 4096.0) + ACCEL_X_BIAS; // 4,096 is the gain per LSB of the measurement reading based on a configuration range of +-8g - 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; - gyro_y = (sensor_data[GYR_Y_H] << 8 | sensor_data[GYR_Y_L]);// * G_GAIN; - gyro_z = (sensor_data[GYR_Z_H] << 8 | sensor_data[GYR_Z_L]);// * G_GAIN; - - //Get the number of degrees - //javey: converted to radians to following SI units - gam->gyro_xVel_p = ((gyro_x / GYRO_SENS) * DEG_TO_RAD) + GYRO_X_BIAS; - gam->gyro_yVel_q = ((gyro_y / GYRO_SENS) * DEG_TO_RAD) + GYRO_Y_BIAS; - gam->gyro_zVel_r = ((gyro_z / GYRO_SENS) * DEG_TO_RAD) + GYRO_Z_BIAS; - - return 0; -} - -////////////////////////////////////////////////// -// LIDAR -////////////////////////////////////////////////// - -int iic0_lidarlite_write(u8 register_addr, u8 data) { - u8 buf[] = {register_addr, data}; - - return XIicPs_MasterSendPolled_ours(&I2C0, buf, 2, LIDARLITE_DEVICE_ADDR); -} - -int iic0_lidarlite_read(u8* recv_buffer, u8 register_addr, int size) { - u8 buf[] = {register_addr}; - int status = 0; - - status = XIicPs_MasterSendPolled_ours(&I2C0, buf, 1, LIDARLITE_DEVICE_ADDR); - status |= XIicPs_MasterRecvPolled(&I2C0, recv_buffer,size, LIDARLITE_DEVICE_ADDR); - return status; -} - -int iic0_lidarlite_init() { - int status = 0; - - // Device Reset & Wake up with default settings - status = iic0_lidarlite_write(0x00, 0x00); - usleep(15000); - - // Enable Free Running Mode and distance measurements with correction - status |= iic0_lidarlite_write(0x11, 0xff); - status |= iic0_lidarlite_write(0x00, 0x04); - - return status; -} - -int iic0_lidarlite_sleep() { - return iic0_lidarlite_write(0x65, 0x84); -} - -int iic0_lidarlite_read_distance(lidar_t *lidar) { - u8 buf[2]; - int status = 0; - - // Read the sensor value - status = iic0_lidarlite_read(buf, 0x8f, 2); - lidar->distance_cm = buf[0] << 8 | buf[1]; - - return status; -} - -/*****************************************************************************/ -/** -* NOTE to MicroCART: This function is originally from the Xilinx library, -* but we noticed that the original function didn't check for a NACK, which -* would cause the original polling function to enter an infinite loop in the -* event of a NACK. Notice that we have added that NACK check at the final -* while loop of this function. -* -* -* This function initiates a polled mode send in master mode. -* -* It sends data to the FIFO and waits for the slave to pick them up. -* If slave fails to remove data from FIFO, the send fails with -* time out. -* -* @param InstancePtr is a pointer to the XIicPs instance. -* @param MsgPtr is the pointer to the send buffer. -* @param ByteCount is the number of bytes to be sent. -* @param SlaveAddr is the address of the slave we are sending to. -* -* @return -* - XST_SUCCESS if everything went well. -* - XST_FAILURE if timed out. -* -* @note This send routine is for polled mode transfer only. -* -****************************************************************************/ -int XIicPs_MasterSendPolled_ours(XIicPs *InstancePtr, u8 *MsgPtr, - int ByteCount, u16 SlaveAddr) -{ - u32 IntrStatusReg; - u32 StatusReg; - u32 BaseAddr; - u32 Intrs; - - /* - * Assert validates the input arguments. - */ - Xil_AssertNonvoid(InstancePtr != NULL); - Xil_AssertNonvoid(MsgPtr != NULL); - Xil_AssertNonvoid(InstancePtr->IsReady == XIL_COMPONENT_IS_READY); - Xil_AssertNonvoid(XIICPS_ADDR_MASK >= SlaveAddr); - - BaseAddr = InstancePtr->Config.BaseAddress; - InstancePtr->SendBufferPtr = MsgPtr; - InstancePtr->SendByteCount = ByteCount; - - XIicPs_SetupMaster(InstancePtr, SENDING_ROLE); - - XIicPs_WriteReg(BaseAddr, XIICPS_ADDR_OFFSET, SlaveAddr); - - /* - * Intrs keeps all the error-related interrupts. - */ - Intrs = XIICPS_IXR_ARB_LOST_MASK | XIICPS_IXR_TX_OVR_MASK | - XIICPS_IXR_TO_MASK | XIICPS_IXR_NACK_MASK; - - /* - * Clear the interrupt status register before use it to monitor. - */ - IntrStatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET); - XIicPs_WriteReg(BaseAddr, XIICPS_ISR_OFFSET, IntrStatusReg); - - /* - * Transmit first FIFO full of data. - */ - TransmitFifoFill(InstancePtr); - - IntrStatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET); - - /* - * Continue sending as long as there is more data and - * there are no errors. - */ - while ((InstancePtr->SendByteCount > 0) && - ((IntrStatusReg & Intrs) == 0)) { - StatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_SR_OFFSET); - - /* - * Wait until transmit FIFO is empty. - */ - if ((StatusReg & XIICPS_SR_TXDV_MASK) != 0) { - IntrStatusReg = XIicPs_ReadReg(BaseAddr, - XIICPS_ISR_OFFSET); - continue; - } - - /* - * Send more data out through transmit FIFO. - */ - TransmitFifoFill(InstancePtr); - } - - /* - * Check for completion of transfer. - */ - // NOTE for MicroCART: Corrected function. Original left for reference. -// while ((XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET) & -// XIICPS_IXR_COMP_MASK) != XIICPS_IXR_COMP_MASK); - while (!(IntrStatusReg & (Intrs | XIICPS_IXR_COMP_MASK))) { - IntrStatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET); - } - - /* - * If there is an error, tell the caller. - */ - if (IntrStatusReg & Intrs) { - return XST_FAILURE; - } - - return XST_SUCCESS; -} - -/*****************************************************************************/ -/* -* NOTE to MicroCART: This function is required by the send polling method above, -* but it was originally static, so we had to copy it word-for-word here. -* -* This function prepares a device to transfers as a master. -* -* @param InstancePtr is a pointer to the XIicPs instance. -* -* @param Role specifies whether the device is sending or receiving. -* -* @return -* - XST_SUCCESS if everything went well. -* - XST_FAILURE if bus is busy. -* -* @note Interrupts are always disabled, device which needs to use -* interrupts needs to setup interrupts after this call. -* -****************************************************************************/ -int XIicPs_SetupMaster(XIicPs *InstancePtr, int Role) -{ - u32 ControlReg; - u32 BaseAddr; - u32 EnabledIntr = 0x0; - - Xil_AssertNonvoid(InstancePtr != NULL); - - BaseAddr = InstancePtr->Config.BaseAddress; - ControlReg = XIicPs_ReadReg(BaseAddr, XIICPS_CR_OFFSET); - - - /* - * Only check if bus is busy when repeated start option is not set. - */ - if ((ControlReg & XIICPS_CR_HOLD_MASK) == 0) { - if (XIicPs_BusIsBusy(InstancePtr)) { - return XST_FAILURE; - } - } - - /* - * Set up master, AckEn, nea and also clear fifo. - */ - ControlReg |= XIICPS_CR_ACKEN_MASK | XIICPS_CR_CLR_FIFO_MASK | - XIICPS_CR_NEA_MASK | XIICPS_CR_MS_MASK; - - if (Role == RECVING_ROLE) { - ControlReg |= XIICPS_CR_RD_WR_MASK; - EnabledIntr = XIICPS_IXR_DATA_MASK |XIICPS_IXR_RX_OVR_MASK; - }else { - ControlReg &= ~XIICPS_CR_RD_WR_MASK; - } - EnabledIntr |= XIICPS_IXR_COMP_MASK | XIICPS_IXR_ARB_LOST_MASK; - - XIicPs_WriteReg(BaseAddr, XIICPS_CR_OFFSET, ControlReg); - - XIicPs_DisableAllInterrupts(BaseAddr); - - return XST_SUCCESS; -} diff --git a/quad/sw/modular_quad_pid/src/initialize_components.c b/quad/sw/modular_quad_pid/src/initialize_components.c deleted file mode 100644 index 91af69ad0b10063fb397bbbe3cd3dd010eaf6391..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/initialize_components.c +++ /dev/null @@ -1,84 +0,0 @@ -/* - * initialize_components.c - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -#include "initialize_components.h" -#include "communication.h" -#include "sensor.h" - -//#define BENCH_TEST - -extern int Xil_AssertWait; - -int protection_loops(modular_structs_t *structs) -{ - int rc_commands[6]; // 6 "receiver_input" elements: Throttle, Pitch, Roll, Yaw, Gear, and Flap - - read_rec_all(rc_commands); - - // wait for RC receiver to connect to transmitter - while(rc_commands[THROTTLE] < 75000) - read_rec_all(rc_commands); - - // wait until throttle is low and the gear switch is engaged (so you don't immediately break out of the main loop below) - // also wait for the flight mode to be set to manual - while(rc_commands[THROTTLE] > 125000 || read_kill(rc_commands[GEAR]) || !read_flap(rc_commands[FLAP])) { - process_received(structs); - read_rec_all(rc_commands); - } - - // let the pilot/observers know that the quad is now active - MIO7_led_on(); - - return 0; -} - -int initializeAllComponents(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) -{ - // Turn off LED 7 to let observers know that the quad is not yet active - MIO7_led_off(); - - // Initialize the controller - control_algorithm_init(parameter_struct); - - // Initialize the logging - initialize_logging(log_struct, parameter_struct); - - // Xilinx given initialization - init_platform(); - - - // Initialize loop timers - if (timer_init()) { - return -1; - } - - // Initialize UART0 (Bluetooth) - if (initUartComms()) { - return -1; - } - - // Initialize I2C controller and start the sensor board - if (iic0_init() == -1) { - return -1; - } - - // Initialize PWM Recorders and Motor outputs - pwm_init(); - - //manual flight mode - user_defined_struct->flight_mode = MANUAL_FLIGHT_MODE; - -#ifndef BENCH_TEST - // Get the first loop data from accelerometer for the gyroscope to use - if(sensor_init(raw_sensor_struct, sensor_struct) == -1) - return -1; -#endif - - return 0; -} diff --git a/quad/sw/modular_quad_pid/src/log_data.c b/quad/sw/modular_quad_pid/src/log_data.c deleted file mode 100644 index cffb7fc05bcf5b280cc45ac26b6902fe2686f08c..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/log_data.c +++ /dev/null @@ -1,172 +0,0 @@ -/* - * log_data.c - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -#include <stdio.h> -#include <stdlib.h> -#include <string.h> -#include "PID.h" -#include "type_def.h" -#include "uart.h" -#include "sleep.h" -#include "log_data.h" -#include "communication.h" -#include "computation_graph.h" -#include "graph_blocks/node_pid.h" -#include "graph_blocks/node_constant.h" -#include "graph_blocks/node_mixer.h" - -// Current index of the log array -int arrayIndex = 0; -// Size of the array -int arraySize = LOG_STARTING_SIZE; - -struct graph_tuple { // Tuple for - int block_id; - int sub_id; -}; - -struct graph_tuple log_outputs[MAX_LOG_NUM]; -struct graph_tuple log_params[MAX_LOG_NUM]; -size_t n_outputs; -size_t n_params; - -float* logArray; -int row_size; - -void addOutputToLog(log_t* log_struct, int controller_id, int output_id) { - if (n_outputs < MAX_LOG_NUM) { - log_outputs[n_outputs].block_id = controller_id; - log_outputs[n_outputs].sub_id = output_id; - n_outputs++; - } -} -void addParamToLog(log_t* log_struct, int controller_id, int param_id) { - if (n_params < MAX_LOG_NUM) { - log_params[n_params].block_id = controller_id; - log_params[n_params].sub_id = param_id; - n_params++; - } -} - -void initialize_logging(log_t* log_struct, parameter_t* ps) { - addOutputToLog(log_struct, ps->alt_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->x_pos_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->y_pos_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->pitch_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->roll_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->yaw_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->pitch_r_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->roll_r_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->yaw_r_pid, PID_CORRECTION); - addOutputToLog(log_struct, ps->cur_pitch, CONST_VAL); - addOutputToLog(log_struct, ps->cur_roll, CONST_VAL); - addOutputToLog(log_struct, ps->cur_yaw, CONST_VAL); - addOutputToLog(log_struct, ps->vrpn_x, CONST_VAL); - addOutputToLog(log_struct, ps->vrpn_y, CONST_VAL); - addOutputToLog(log_struct, ps->vrpn_alt, CONST_VAL); - addOutputToLog(log_struct, ps->vrpn_pitch, CONST_VAL); - addOutputToLog(log_struct, ps->vrpn_roll, CONST_VAL); - addOutputToLog(log_struct, ps->x_set, CONST_VAL); - addOutputToLog(log_struct, ps->y_set, CONST_VAL); - addOutputToLog(log_struct, ps->alt_set, CONST_VAL); - addOutputToLog(log_struct, ps->mixer, MIXER_PWM0); - addOutputToLog(log_struct, ps->mixer, MIXER_PWM1); - addOutputToLog(log_struct, ps->mixer, MIXER_PWM2); - addOutputToLog(log_struct, ps->mixer, MIXER_PWM3); - - // TODO: Make this not stupid. Adding 6 for IMU and 1 for timestamp - row_size = n_outputs + n_params + 6 + 1; - logArray = malloc(sizeof(float) * row_size * LOG_STARTING_SIZE); -} - - -int log_data(log_t* log_struct, parameter_t* ps) -{ - if(arrayIndex >= arraySize - 1) - { - return 1; - } - float* thisRow = &logArray[arrayIndex * row_size * sizeof(float)]; - int offset = 0; - thisRow[offset++] = log_struct->time_stamp; - thisRow[offset++] = log_struct->gam.accel_x; - thisRow[offset++] = log_struct->gam.accel_y; - thisRow[offset++] = log_struct->gam.accel_z; - thisRow[offset++] = log_struct->gam.gyro_xVel_p; - thisRow[offset++] = log_struct->gam.gyro_yVel_q; - thisRow[offset++] = log_struct->gam.gyro_zVel_r; - - int i; - for (i = 0; i < n_params; i++) { - thisRow[offset++] = graph_get_param_val(ps->graph, log_params[i].block_id, log_params[i].sub_id); - } - for (i = 0; i < n_outputs; i++) { - thisRow[offset++] = graph_get_output(ps->graph, log_outputs[i].block_id, log_outputs[i].sub_id); - } - - arrayIndex++; - return 0; -} - - -/** - * Prints all the log information. - * - * TODO: This should probably be transmitting in binary instead of ascii - */ - -void printLogging(log_t* log_struct, parameter_t* ps){ - int i;//, j; - char buf[2048] = {}; - buf[0] = 0; // Mark buffer as size 0 - char header1[256] = {}; - char header2[1024] = {}; - - sprintf(header1, "time,accel_x,accel_y,accel_z,gyro_x,gyro_y,gyro_z"); - - int end = 0; - // 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; - const char* output_name = ps->graph->nodes[log_params[i].block_id].type->param_names[log_params[i].sub_id]; - end += sprintf(&header2[end], ",%s-%s", block_name, output_name); - } - // Print all the recorded block outputs - for (i = 0; i < n_outputs; i++) { - const char* block_name = ps->graph->nodes[log_outputs[i].block_id].name; - const char* param_name = ps->graph->nodes[log_outputs[i].block_id].type->output_names[log_outputs[i].sub_id]; - end += sprintf(&header2[end], ",%s-%s", block_name, param_name); - } - end += sprintf(&header2[end], "\n"); - - - strcat(buf,header1); - strcat(buf,header2); - - send_data(LOG_ID, 0, buf, strlen(buf)); - - /*************************/ - /* print & send log data */ - for(i = 0; i < arrayIndex; i++){ - int size = format_log(i, log_struct, buf); - send_data(LOG_ID, 0, buf, size); - } -} - -int format_log(int idx, log_t* log_struct, char* buf) { - int i; - int end = 0; - - float* row = &logArray[idx * row_size * sizeof(float)];\ - - end += sprintf(&buf[end], "%f", row[0]); - for (i = 1; i < row_size; i++) { - end += sprintf(&buf[end], ",%f", row[i]); - } - end += sprintf(&buf[end], "\n"); - return end; -} diff --git a/quad/sw/modular_quad_pid/src/mio7_led.c b/quad/sw/modular_quad_pid/src/mio7_led.c deleted file mode 100644 index 4742add5b48abf1f3a6998dc0e8e0aaa4a54cc87..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/mio7_led.c +++ /dev/null @@ -1,53 +0,0 @@ -/* - * mio7_led.c - * - * Created on: Feb 20, 2016 - * Author: Amy Seibert - */ - - #include "mio7_led.h" - -void flash_MIO_7_led(int how_many_times, int ms_between_flashes) -{ - if(how_many_times <= 0) - return; - - while(how_many_times) - { - MIO7_led_on(); - - usleep(ms_between_flashes * 500); - - MIO7_led_off(); - - usleep(ms_between_flashes * 500); - - how_many_times--; - } -} - -void MIO7_led_off() -{ - XGpioPs Gpio; - - XGpioPs_Config * ConfigPtr = XGpioPs_LookupConfig(XPAR_PS7_GPIO_0_DEVICE_ID); - XGpioPs_CfgInitialize(&Gpio, ConfigPtr, ConfigPtr->BaseAddr); - - XGpioPs_SetDirectionPin(&Gpio, 7, 1); - - // Disable LED - XGpioPs_WritePin(&Gpio, 7, 0x00); -} - -void MIO7_led_on() -{ - XGpioPs Gpio; - - XGpioPs_Config * ConfigPtr = XGpioPs_LookupConfig(XPAR_PS7_GPIO_0_DEVICE_ID); - XGpioPs_CfgInitialize(&Gpio, ConfigPtr, ConfigPtr->BaseAddr); - - XGpioPs_SetDirectionPin(&Gpio, 7, 1); - - // Enable LED - XGpioPs_WritePin(&Gpio, 7, 0x01); -} diff --git a/quad/sw/modular_quad_pid/src/send_actuator_commands.c b/quad/sw/modular_quad_pid/src/send_actuator_commands.c deleted file mode 100644 index 3ef6f1a87140fa572d0118c3fc73b3bdf4fb667b..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/send_actuator_commands.c +++ /dev/null @@ -1,20 +0,0 @@ -/* - * send_actuator_commands.c - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -#include "send_actuator_commands.h" -#include "util.h" - -int send_actuator_commands(log_t* log_struct, actuator_command_t* actuator_command_struct) -{ - int i; - // write the PWMs to the motors - for (i = 0; i < 4; i++) - pwm_write_channel(actuator_command_struct->pwms[i], i); - - return 0; -} - diff --git a/quad/sw/modular_quad_pid/src/timer.c b/quad/sw/modular_quad_pid/src/timer.c deleted file mode 100644 index c82b373a55381b59cc608244622ab65d9f8380e3..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/timer.c +++ /dev/null @@ -1,77 +0,0 @@ -/* - * timer.c - * - * Created on: Feb 24, 2016 - * Author: ucart - */ - - - -#include "timer.h" -#include "xtime_l.h" -#include <xtmrctr.h> - -static XTime before = 0; -static XTime after = 0; -static XTmrCtr axi_timer; -static float LOOP_TIME; -static float time_stamp = 0; - -int timer_init() -{ - - // using a axi_timer core because we've had problems with the Global Timer - return XTmrCtr_Initialize(&axi_timer, XPAR_AXI_TIMER_0_DEVICE_ID); -} - -int timer_start_loop() -{ - //timing code - LOOP_TIME = ((float)(after - before)) / ((float) COUNTS_PER_SECOND); - XTime_GetTime(&before); - XTmrCtr_Reset(&axi_timer, 0); - XTmrCtr_Start(&axi_timer, 0); - - return 0; -} - -int timer_end_loop(log_t *log_struct) -{ - // get number of useconds its taken to run the loop thus far - int usec_loop = XTmrCtr_GetValue(&axi_timer, 0) / (PL_CLK_CNTS_PER_USEC); - - // attempt to make each loop run for the same amount of time - while(usec_loop < DESIRED_USEC_PER_LOOP) - { - usec_loop = XTmrCtr_GetValue(&axi_timer, 0) / (PL_CLK_CNTS_PER_USEC); - } - -// static int counter = 0; -// counter++; -// if(counter % 50 == 0) -// printf("usec_loop: %d\n", usec_loop); - - //timing code - XTime_GetTime(&after); - time_stamp += LOOP_TIME; - XTmrCtr_Stop(&axi_timer, 0); - - // for timing debugging, its a separate hardware PL timer not associated with the PS - // used this to compare to the PS clock to make sure the timing matched -// float axi_timer_val = ((float)XTmrCtr_GetValue(&axi_timer, 0)) / ((float)100000000); - - - // Log the timing information - log_struct->time_stamp = time_stamp; - log_struct->time_slice = LOOP_TIME; - - return 0; -} - -float get_last_loop_time() { - return LOOP_TIME; -} - -uint32_t timer_get_count() { - return XTmrCtr_GetValue(&axi_timer, 0); -} diff --git a/quad/sw/modular_quad_pid/src/uart.c b/quad/sw/modular_quad_pid/src/uart.c deleted file mode 100644 index 8328bed7b4f35388240e8c075b5e92cf4e7c4f70..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/uart.c +++ /dev/null @@ -1,381 +0,0 @@ -/* - * uart.c - * - * Created on: Nov 10, 2014 - * Author: ucart - */ - - -#include <stdlib.h> -#include <stdio.h> -#include <string.h> -#include "uart.h" -#include <xuartps.h> -#include <xstatus.h> - -// Global PS's -XUartPs* _Uart0PS; -XUartPs* _Uart1PS; -static INTC Intc; - -//This is copied from xuart driver -/***************************************************/ - -#define XUARTPS_MAX_BAUD_ERROR_RATE 3 /* max % error allowed */ -int XUartPs_SetBaudRate_ours(XUartPs *InstancePtr, u32 BaudRate) -{ - u8 IterBAUDDIV; /* Iterator for available baud divisor values */ - u32 BRGR_Value; /* Calculated value for baud rate generator */ - u32 CalcBaudRate; /* Calculated baud rate */ - u32 BaudError; /* Diff between calculated and requested baud rate */ - u32 Best_BRGR = 0; /* Best value for baud rate generator */ - u8 Best_BAUDDIV = 0; /* Best value for baud divisor */ - u32 Best_Error = 0xFFFFFFFF; - u32 PercentError; - u32 ModeReg; - u32 InputClk; - - /* - * Asserts validate the input arguments - */ - Xil_AssertNonvoid(InstancePtr != NULL); - Xil_AssertNonvoid(InstancePtr->IsReady == XIL_COMPONENT_IS_READY); - //Xil_AssertNonvoid(BaudRate <= XUARTPS_MAX_RATE); - Xil_AssertNonvoid(BaudRate >= XUARTPS_MIN_RATE); - - /* - * Make sure the baud rate is not impossilby large. - * Fastest possible baud rate is Input Clock / 2. - */ - if ((BaudRate * 2) > InstancePtr->Config.InputClockHz) { - return XST_UART_BAUD_ERROR; - } - /* - * Check whether the input clock is divided by 8 - */ - ModeReg = XUartPs_ReadReg( InstancePtr->Config.BaseAddress, - XUARTPS_MR_OFFSET); - - InputClk = InstancePtr->Config.InputClockHz; - if(ModeReg & XUARTPS_MR_CLKSEL) { - InputClk = InstancePtr->Config.InputClockHz / 8; - } - - /* - * Determine the Baud divider. It can be 4to 254. - * Loop through all possible combinations - */ - for (IterBAUDDIV = 4; IterBAUDDIV < 255; IterBAUDDIV++) { - - /* - * Calculate the value for BRGR register - */ - BRGR_Value = InputClk / (BaudRate * (IterBAUDDIV + 1)); - - /* - * Calculate the baud rate from the BRGR value - */ - CalcBaudRate = InputClk/ (BRGR_Value * (IterBAUDDIV + 1)); - - /* - * Avoid unsigned integer underflow - */ - if (BaudRate > CalcBaudRate) { - BaudError = BaudRate - CalcBaudRate; - } - else { - BaudError = CalcBaudRate - BaudRate; - } - - /* - * Find the calculated baud rate closest to requested baud rate. - */ - if (Best_Error > BaudError) { - - Best_BRGR = BRGR_Value; - Best_BAUDDIV = IterBAUDDIV; - Best_Error = BaudError; - } - } - - /* - * Make sure the best error is not too large. - */ - PercentError = (Best_Error * 100) / BaudRate; - if (XUARTPS_MAX_BAUD_ERROR_RATE < PercentError) { - return XST_UART_BAUD_ERROR; - } - - /* - * Disable TX and RX to avoid glitches when setting the baud rate. - */ - XUartPs_DisableUart(InstancePtr); - - XUartPs_WriteReg(InstancePtr->Config.BaseAddress, - XUARTPS_BAUDGEN_OFFSET, Best_BRGR); - XUartPs_WriteReg(InstancePtr->Config.BaseAddress, - XUARTPS_BAUDDIV_OFFSET, Best_BAUDDIV); - - /* - * Enable device - */ - XUartPs_EnableUart(InstancePtr); - - InstancePtr->BaudRate = BaudRate; - - return XST_SUCCESS; - -} - -/***************************************************/ - -/************************************************/ -/************** Main UART Interface *************/ - -XUartPs* uart_init(XUartPs* uartps_ptr, u16 deviceID, int baudRate) { - XUartPs_Config* config = XUartPs_LookupConfig(deviceID); - - //Configure XUartPs instance - int Status = XUartPs_CfgInitialize(uartps_ptr, config, config->BaseAddress); - if (Status != XST_SUCCESS){ - return NULL; - } - - //Set Baudrate for BT - //XUartPs_SetBaudRate(uartps_ptr, baudRate); - XUartPs_SetBaudRate_ours(uartps_ptr, baudRate); - - return uartps_ptr; -} - -void uart_clearFIFOs(XUartPs* uartps_ptr) { - //Get UART0 Control Register and clear the TX and RX Fifos - int* uart_ctrl_reg = (int*) uartps_ptr->Config.BaseAddress; - *uart_ctrl_reg |= 0x00000003; // clear TX & RX -} - -void uart_sendByte(XUartPs* uartps_ptr, char data) { - XUartPs_SendByte(uartps_ptr->Config.BaseAddress, data); -} - -void uart_sendStr(XUartPs* uartps_ptr, char* str) { - uart_sendBytes(uartps_ptr, str, strlen(str)); -} - -void uart_sendBytes(XUartPs* uartps_ptr, char* data, int numBytes) { - while (uart_isSending(uartps_ptr)) - ; - - int done = 0; - while (done < numBytes) { - done += XUartPs_Send(uartps_ptr, (unsigned char*) (&data[done]), numBytes - done); - } -} - -int uart_isSending(XUartPs* uartps_ptr) { - return XUartPs_IsSending(uartps_ptr); -} - -int uart_hasData(XUartPs* uartps_ptr) { - return XUartPs_IsReceiveData(uartps_ptr->Config.BaseAddress); -} - -void uart_recvBytes(XUartPs* uartps_ptr, char* buffer, int numBytes) { - int received = 0; - while (received < numBytes) { - received += XUartPs_Recv(uartps_ptr, (unsigned char*) &buffer[received], (numBytes - received)); - } -} - -char uart_recvByte(XUartPs* uartps_ptr) { - return XUartPs_RecvByte(uartps_ptr->Config.BaseAddress); - //char buffer[1]; - //XUartPs_Recv(uartps_ptr, (unsigned char*) &buffer[0], 1); - -// return buffer[0]; -} - - -/*****************************************************************************/ -/** -* -* This function sets up the interrupt system so interrupts can occur for the -* Uart. This function is application-specific. -* -* @param IntcInstancePtr is a pointer to the instance of the INTC. -* @param UartInstancePtr contains a pointer to the instance of the UART -* driver which is going to be connected to the interrupt -* controller. -* @param UartIntrId is the interrupt Id and is typically -* XPAR_<UARTPS_instance>_INTR value from xparameters.h. -* -* @return XST_SUCCESS if successful, otherwise XST_FAILURE. -* -* @note None. -* -****************************************************************************/ -int SetupInterruptSystem(XUartPs *UartInstancePtr, u16 UartIntrId, Xil_ExceptionHandler handler) -{ - int Status; - - XScuGic_Config *IntcConfig; /* Config for interrupt controller */ - - /* Initialize the interrupt controller driver */ - IntcConfig = XScuGic_LookupConfig(INTC_DEVICE_ID); - if (NULL == IntcConfig) { - return XST_FAILURE; - } - - Status = XScuGic_CfgInitialize(&Intc, IntcConfig, - IntcConfig->CpuBaseAddress); - if (Status != XST_SUCCESS) { - return XST_FAILURE; - } - - /* - * Connect the interrupt controller interrupt handler to the - * hardware interrupt handling logic in the processor. - */ - Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_INT, - (Xil_ExceptionHandler) XScuGic_InterruptHandler, - &Intc); - - /* - * Connect a device driver handler that will be called when an - * interrupt for the device occurs, the device driver handler - * performs the specific interrupt processing for the device - */ - Status = XScuGic_Connect(&Intc, UartIntrId, - handler, - (void *) UartInstancePtr); - if (Status != XST_SUCCESS) { - return XST_FAILURE; - } - - /* Enable the interrupt for the device */ - XScuGic_Enable(&Intc, UartIntrId); - - /* Enable interrupts */ - Xil_ExceptionEnable(); - - return XST_SUCCESS; -} -/************************************************/ -/************************************************/ - - - - - -/************************************************/ -/********** UART 0 convenience methods **********/ - -XUartPs* uart0_init(u16 deviceID, int baudRate){ - if (_Uart0PS) { - free(_Uart0PS); - } - _Uart0PS = malloc(sizeof(XUartPs)); - return uart_init(_Uart0PS, deviceID, baudRate); -} - -// Initializes the interrupt system for UART 0 -int uart0_int_init(u16 UartIntrId, Xil_ExceptionHandler handler) { - return SetupInterruptSystem(_Uart0PS, UartIntrId, handler); -} - -void uart0_clearFIFOs(){ - uart_clearFIFOs(_Uart0PS); -} - -void uart0_sendByte(u8 data){ - uart_sendByte(_Uart0PS, data); -} - -void uart0_sendStr(char* str) { - uart_sendStr(_Uart0PS, str); -} - -void uart0_sendMetaData(metadata_t md) -{ - uart0_sendByte(md.begin_char); - uart0_sendByte(md.msg_type & 0x00ff); - uart0_sendByte((md.msg_type >> 8) & 0x00ff); - uart0_sendByte(md.msg_id & 0x00ff); - uart0_sendByte((md.msg_id >> 8) & 0x00ff); - uart0_sendByte(md.data_len & 0x00ff); - uart0_sendByte((md.data_len >> 8) & 0x00ff); -} - -void uart0_sendBytes(char* data, int numBytes){ - uart_sendBytes(_Uart0PS, data, numBytes); -} - -int uart0_isSending(){ - return uart_isSending(_Uart0PS); -} - -int uart0_hasData(){ - return uart_hasData(_Uart0PS); -} - -void uart0_recvBytes(char* buffer, int numBytes) { - uart_recvBytes(_Uart0PS, buffer, numBytes); -} - -char uart0_recvByte() { - return uart_recvByte(_Uart0PS); -} - -/************************************************/ -/************************************************/ - - - - - - -/************************************************/ -/********** UART 1 convenience methods **********/ - -XUartPs* uart1_init(u16 deviceID, int baudRate){ - if (_Uart1PS) { - free(_Uart1PS); - } - _Uart1PS = malloc(sizeof(XUartPs)); - return uart_init(_Uart1PS, deviceID, baudRate); -} - -void uart1_clearFIFOs(){ - uart_clearFIFOs(_Uart1PS); -} - -void uart1_sendByte(char data){ - uart_sendByte(_Uart1PS, data); -} - -void uart1_sendStr(char* str) { - uart_sendStr(_Uart1PS, str); -} - -void uart1_sendBytes(char* data, int numBytes){ - uart_sendBytes(_Uart1PS, data, numBytes); -} - -int uart1_isSending(){ - return uart_isSending(_Uart1PS); -} - -int uart1_hasData(){ - return uart_hasData(_Uart1PS); -} - -void uart1_recvBytes(char* buffer, int numBytes) { - uart_recvBytes(_Uart1PS, buffer, numBytes); -} - -char uart1_recvByte() { - return uart_recvByte(_Uart1PS); -} - -/************************************************/ - diff --git a/quad/sw/modular_quad_pid/src/uart.h b/quad/sw/modular_quad_pid/src/uart.h deleted file mode 100644 index 6629e21afcfe8aed1ffa66685744c3023146cc61..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/uart.h +++ /dev/null @@ -1,82 +0,0 @@ -/* - * uart.h - * - * Created on: Nov 10, 2014 - * Author: ucart - */ - -#ifndef UART_H_ -#define UART_H_ - -#include "xparameters.h" -#include "xuartps.h" -#include "xscugic.h" -#include "communication.h" - -#define PACKET_START_CHAR 2 -#define PACKET_END_CHAR 3 -#define UPDATE_SIZE 28 - -#define INTC XScuGic // Interrupt controller type -#define INTC_DEVICE_ID XPAR_SCUGIC_SINGLE_DEVICE_ID - -extern XUartPs* _Uart0PS; -extern XUartPs* _Uart1PS; - - -/************************************************/ -/************** Main UART Interface *************/ -XUartPs* uart_init(XUartPs* uartps_ptr, u16 deviceID, int baudRate); -void uart_clearFIFOs(XUartPs* uartps_ptr); -void uart_sendByte(XUartPs* uartps_ptr, char data); -void uart_sendStr(XUartPs* uartps_ptr, char* str); -void uart_sendBytes(XUartPs* uartps_ptr, char* data, int numBytes); -int uart_isSending(XUartPs* uartps_ptr); -int uart_hasData(XUartPs* uartps_ptr); - -//char uart_recvByte(); // block until char received - -//int uart_recvBytes(char* buffer, int numBytes, int timeoutMicros); // block until all received - -//void uart_recvCallback(void (*func)(char data)); - -void uart_recvBytes(XUartPs* uartps_ptr, char* buffer, int numBytes); - -char uart_recvByte(XUartPs* uartps_ptr); -/************************************************/ -/************************************************/ - - - -/************************************************/ -/********** UART 0 convenience methods **********/ -XUartPs* uart0_init(u16 deviceID, int baudRate); -int uart0_int_init(u16 UartIntrId, Xil_ExceptionHandler handler); -void uart0_clearFIFOs(); -void uart0_sendByte(u8 data); -void uart0_sendStr(char* data); -void uart0_sendBytes(char* data, int numBytes); -int uart0_isSending(); -int uart0_hasData(); -void uart0_recvBytes(char* buffer, int numBytes); -char uart0_recvByte(); -void uart0_sendMetaData(metadata_t md); -/************************************************/ -/************************************************/ - - - -/************************************************/ -/********** UART 1 convenience methods **********/ -XUartPs* uart1_init(u16 deviceID, int baudRate); -void uart1_clearFIFOs(); -void uart1_sendByte(char data); -void uart1_sendStr(char* data); -void uart1_sendBytes(char* data, int numBytes); -int uart1_isSending(); -int uart1_hasData(); -void uart1_recvBytes(char* buffer, int numBytes); -char uart1_recvByte(); -/************************************************/ - -#endif /* UART_H_ */ diff --git a/quad/sw/modular_quad_pid/src/uart_buff.c b/quad/sw/modular_quad_pid/src/uart_buff.c deleted file mode 100644 index 56f5c1d90274bc80e0150fccc2603631b042aedd..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/uart_buff.c +++ /dev/null @@ -1,417 +0,0 @@ -#include <stdio.h> -#include "uart_buff.h" -#include <stdlib.h> - -// function prototype declarations specific to the circular buffer -void uart_buff_scan_packet(); -void uart_buff_scan_packet_start(); -void uart_buff_scan_packet_size(); -size_t uart_buff_packet_size(); -size_t uart_buff_calc_index(int); - -static volatile u8 buff[UART_MAX_BUFF_SIZE]; -u8 packet_buff[UART_MAX_PACKET_SIZE]; - -static size_t start = 0; -static volatile size_t end = 0; -static size_t packet_data_length = 0; - -static u8 packet_ready = 0; - -// TODO: Delete these debugging variables -static u32 packets_processed = 0; - -/** - * Put a byte into the buffer. - */ -void uart_buff_add_u8(u8 c) { - if (uart_buff_full()) { - return; - } - - buff[end] = c; - end += 1; - if (end >= UART_MAX_BUFF_SIZE) { - end -= UART_MAX_BUFF_SIZE; - } -} - -/** - * Scan for a packet, updating any necessary indices and flags. - */ -void uart_buff_scan_packet() { - size_t scan_limit = uart_buff_size(); - size_t scan_iteration = 0; - while (!packet_ready && scan_iteration < scan_limit) { - scan_iteration += 1; - - if (buff[start] != 0xBE) { - start += 1; - if (start >= UART_MAX_BUFF_SIZE) { - start -= UART_MAX_BUFF_SIZE; - } - continue; - } - - if (uart_buff_size() < UART_PACKET_HEADER_SIZE) { - // Haven't received the "length" bytes yet. Check back later. - break; - } - - packet_data_length = (uart_buff_get_u8(6) << 8) | uart_buff_get_u8(5); - if (uart_buff_packet_size() > UART_MAX_PACKET_SIZE) { - // Packet size is too big. Abort this packet. - start += 1; - if (start >= UART_MAX_BUFF_SIZE) { - start -= UART_MAX_BUFF_SIZE; - } - continue; - } - - if (uart_buff_size() < uart_buff_packet_size()) { - // Haven't received the whole packet. Check back later. - break; - } - - packet_ready = 1; - } -} - -/** - * Return 1 if a packet is ready to processed, 0 otherwise. - */ -int uart_buff_packet_ready() { - if (!packet_ready) { - uart_buff_scan_packet(); - } - return packet_ready; -} - -/** - * Retrieve a 8-bit from the buffer according to the given offset with respect - * to the start index of the current packet. - */ -u8 uart_buff_get_u8(size_t offset) { - size_t index = start + offset; - - if (index >= UART_MAX_BUFF_SIZE) { - index -= UART_MAX_BUFF_SIZE; - } - - return buff[index]; -} - -/** - * Retrieve a 16-bit unsigned integer from the buffer according to the given - * offset with respect to the start index of the current packet. - */ -u16 uart_buff_get_u16(size_t offset) { - size_t index_1 = start + offset + 1; - size_t index = start + offset; - - // Check common cases first - if (index_1 < UART_MAX_BUFF_SIZE) { - // in range, no need to correct indices - } - else if (index >= UART_MAX_BUFF_SIZE) { - index_1 -= UART_MAX_BUFF_SIZE; - index -= UART_MAX_BUFF_SIZE; - } - else { - index_1 -= UART_MAX_BUFF_SIZE; - } - - return buff[index_1] << 8 - | buff[index]; -} - -/** - * Retrieve a 32-bit from the buffer according to the given offset with respect - * to the start index of the current packet. - */ -u32 uart_buff_get_u32(size_t offset) { - size_t index_3 = start + offset + 3; - size_t index_2 = start + offset + 2; - size_t index_1 = start + offset + 1; - size_t index = start + offset; - - if (index_3 < UART_MAX_BUFF_SIZE) { - // in range, no need to correct indices - } - else if (index >= UART_MAX_BUFF_SIZE) { - index_3 -= UART_MAX_BUFF_SIZE; - index_2 -= UART_MAX_BUFF_SIZE; - index_1 -= UART_MAX_BUFF_SIZE; - index -= UART_MAX_BUFF_SIZE; - } - else { - index_3 = uart_buff_calc_index(index_3); - index_2 = uart_buff_calc_index(index_2); - index_1 = uart_buff_calc_index(index_1); - index = uart_buff_calc_index(index); - } - - return buff[index_3] << 24 - | buff[index_2] << 16 - | buff[index_1] << 8 - | buff[index]; -} - -/** - * Retrieve a 8-bit unsigned integer from the buffer according to - * the given offset with respect to the start of the data portion - * of the current packet. - * - * This has undefined behavior if a packet is not ready. - */ -u8 uart_buff_data_get_u8(size_t offset) { - size_t index = start + UART_PACKET_HEADER_SIZE + offset; - - if (index >= UART_MAX_BUFF_SIZE) { - index -= UART_MAX_BUFF_SIZE; - } - - return buff[index]; -} - -/** - * Retrieve a 16-bit unsigned integer from the buffer according to - * the given offset with respect to the start of the data portion - * of the current packet. - * - * This has undefined behavior if a packet is not ready. - */ -u16 uart_buff_data_get_u16(size_t offset) { - size_t index_1 = start + UART_PACKET_HEADER_SIZE + offset + 1; - size_t index = start + UART_PACKET_HEADER_SIZE + offset; - - // Check common cases first - if (index_1 < UART_MAX_BUFF_SIZE) { - // in range, no need to correct indices - } - else if (index >= UART_MAX_BUFF_SIZE) { - index_1 -= UART_MAX_BUFF_SIZE; - index -= UART_MAX_BUFF_SIZE; - } - else { - index_1 -= UART_MAX_BUFF_SIZE; - } - - return buff[index_1] << 8 - | buff[index]; -} - -/** - * Retrieve a 32-bit unsigned integer from the buffer according to - * the given offset with respect to the start of the data portion - * of the current packet. - * - * This has undefined behavior if a packet is not ready. - */ -u32 uart_buff_data_get_u32(size_t offset) { - size_t index_3 = start + UART_PACKET_HEADER_SIZE + offset + 3; - size_t index_2 = start + UART_PACKET_HEADER_SIZE + offset + 2; - size_t index_1 = start + UART_PACKET_HEADER_SIZE + offset + 1; - size_t index = start + UART_PACKET_HEADER_SIZE + offset; - - if (index_3 < UART_MAX_BUFF_SIZE) { - // in range, no need to correct indices - } - else if (index >= UART_MAX_BUFF_SIZE) { - index_3 -= UART_MAX_BUFF_SIZE; - index_2 -= UART_MAX_BUFF_SIZE; - index_1 -= UART_MAX_BUFF_SIZE; - index -= UART_MAX_BUFF_SIZE; - } - else { - index_3 = uart_buff_calc_index(index_3); - index_2 = uart_buff_calc_index(index_2); - index_1 = uart_buff_calc_index(index_1); - index = uart_buff_calc_index(index); - } - - return buff[index_3] << 24 - | buff[index_2] << 16 - | buff[index_1] << 8 - | buff[index]; -} - -/** - * Retrieve a 32-bit floating point number from the buffer according to the - * given offset with respect to the start of the data portion of the current - * packet. - * - * This has undefined behavior if a packet is not ready. - */ -float uart_buff_data_get_float(size_t offset) { - size_t index_3 = start + UART_PACKET_HEADER_SIZE + offset + 3; - size_t index_2 = start + UART_PACKET_HEADER_SIZE + offset + 2; - size_t index_1 = start + UART_PACKET_HEADER_SIZE + offset + 1; - size_t index = start + UART_PACKET_HEADER_SIZE + offset; - - if (index_3 < UART_MAX_BUFF_SIZE) { - // in range, no need to correct indices - } - else if (index >= UART_MAX_BUFF_SIZE) { - index_3 -= UART_MAX_BUFF_SIZE; - index_2 -= UART_MAX_BUFF_SIZE; - index_1 -= UART_MAX_BUFF_SIZE; - index -= UART_MAX_BUFF_SIZE; - } - else { - index_3 = uart_buff_calc_index(index_3); - index_2 = uart_buff_calc_index(index_2); - index_1 = uart_buff_calc_index(index_1); - index = uart_buff_calc_index(index); - } - - union { - float f; - int i; - } x; - - x.i = buff[index_3] << 24 - | buff[index_2] << 16 - | buff[index_1] << 8 - | buff[index]; - - return x.f; -} - -/** - * Move the start index of the buffer to the end of the current packet. - * If a packet is not ready, this function does nothing. - */ -void uart_buff_consume_packet() { - if (!packet_ready) { - return; - } - - start = uart_buff_calc_index(start + uart_buff_packet_size()); - packet_ready = 0; - packets_processed += 1; -} - -/** - * Return the current number of bytes held in the buffer. - */ -size_t uart_buff_size() { - int size = end - start; - if (size < 0) { - size += UART_MAX_BUFF_SIZE; - } - return size; -} - -/** - * Return the length of the data portion of the current packet. - */ -size_t uart_buff_data_length() { - return packet_data_length; -} - -/** - * Return the size of the current packet. - */ -inline -size_t uart_buff_packet_size() { - return UART_PACKET_HEADER_SIZE + packet_data_length + 1; -} - -/** - * Return 1 if the buffer is empty, 0 otherwise. - */ -int uart_buff_empty() { - return start == end; -} - -/** - * Return 1 if the buffer is full, 0 otherwise. - */ -int uart_buff_full() { - int effective_end = end + 1; - if (effective_end >= UART_MAX_BUFF_SIZE) { - effective_end -= UART_MAX_BUFF_SIZE; - } - return start == effective_end; -} - -/** - * Calculate the actual index from the given index, wrapping around - * the edges of the circular buffer if necessary. - */ -size_t uart_buff_calc_index(int given_index) { - int actual_index = given_index; - if (actual_index >= UART_MAX_BUFF_SIZE) { - actual_index -= UART_MAX_BUFF_SIZE; - } - return actual_index; -} - -/** - * Return a pointer to the start of the packet. - */ -char * uart_buff_get_raw(size_t *packet_size) { - // Copy packet into temp buffer - *packet_size = uart_buff_packet_size(); - int i; - for (i = 0; i < *packet_size; i += 1) { - packet_buff[i] = uart_buff_get_u8(i); - } - return packet_buff; -} - -/** - * Print the buffer with a pretty ASCII art image. - */ -void uart_buff_print() { - size_t packet_size = uart_buff_packet_size(); - size_t data_start = uart_buff_calc_index(start + UART_PACKET_HEADER_SIZE); - size_t data_end = uart_buff_calc_index(start + packet_size); - int i; - printf("buffer size = %zu\n", uart_buff_size()); - puts("Buffer:"); - puts(".--."); - puts("| |"); - puts("| v"); - for (i = 0; i < UART_MAX_BUFF_SIZE; i += 1) { - printf("| %02X", buff[i]); - if (i == start) { - printf("<-- start"); - } - if (packet_ready) { - if (i == data_start) { - printf("<-- data start"); - } - if (i == data_end) { - printf("<-- data end"); - } - } - if (i == end) { - printf("<-- end"); - } - printf("\n"); - } - puts("| |"); - puts("'--'"); -} - -/** - * Reset the state of the buffer. - */ -void uart_buff_reset() { - start = 0; - end = 0; - int i; - for (i = 0; i < UART_MAX_BUFF_SIZE; i += 1) { - buff[i] = 0; - } - packet_ready = 0; -} - -/** - * Return the total number of packets processed. - */ -u32 uart_buff_packets_processed() { - return packets_processed; -} diff --git a/quad/sw/modular_quad_pid/src/uart_buff.h b/quad/sw/modular_quad_pid/src/uart_buff.h deleted file mode 100644 index 99aadd06e17f632e1e4132d14bfefe4218b5b4f5..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/uart_buff.h +++ /dev/null @@ -1,29 +0,0 @@ -#ifndef CIRC_BUFF_H -#define CIRC_BUFF_H - -#include "xil_types.h" - -#define UART_MAX_BUFF_SIZE 2048 -#define UART_MAX_PACKET_SIZE 256 -#define UART_PACKET_HEADER_SIZE 7 - -void uart_buff_add_u8(u8); -int uart_buff_packet_ready(); -u8 uart_buff_get_u8(size_t); -u16 uart_buff_get_u16(size_t); -u32 uart_buff_get_u32(size_t); -u8 uart_buff_data_get_u8(size_t); -u16 uart_buff_data_get_u16(size_t); -u32 uart_buff_data_get_u32(size_t); -float uart_buff_data_get_float(size_t); -void uart_buff_consume_packet(); -size_t uart_buff_size(); -size_t uart_buff_data_length(); -int uart_buff_empty(); -int uart_buff_full(); -char * uart_buff_get_raw(size_t *); -void uart_buff_print(); -u32 uart_buff_packets_processed(); -void uart_buff_reset(); - -#endif diff --git a/quad/sw/modular_quad_pid/src/util.c b/quad/sw/modular_quad_pid/src/util.c deleted file mode 100644 index be07d38187f621dc63405b031eb5ff3131d81a5b..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/util.c +++ /dev/null @@ -1,517 +0,0 @@ -/* - * util.c - * - * Created on: Oct 11, 2014 - * Author: ucart - */ - -#include "util.h" - -#include <stdlib.h> -#include <stdio.h> -#include <string.h> -#include <math.h> -#include <xgpiops.h> -#include "PID.h" -#include "log_data.h" -#include <sleep.h> -#include "controllers.h" -#include "xparameters.h" -#include "uart.h" - -extern int motor0_bias, motor1_bias, motor2_bias, motor3_bias; -//Global variable representing the current pulseW -int pulseW = pulse_throttle_low; - -/** - * Initializes the PWM output components. - * Default pulse length = 1 ms - * Default period length = 2.33 ms - */ -void pwm_init() { - - int* pwm_0 = (int*) PWM_0_ADDR + PWM_PERIOD; - int* pwm_1 = (int*) PWM_1_ADDR + PWM_PERIOD; - int* pwm_2 = (int*) PWM_2_ADDR + PWM_PERIOD; - int* pwm_3 = (int*) PWM_3_ADDR + PWM_PERIOD; - - // Initializes all the PWM address to have the correct period width at 450 hz - *pwm_0 = period_width; - *pwm_1 = period_width; - *pwm_2 = period_width; - *pwm_3 = period_width; - // Initializes the PWM pulse lengths to be 1 ms - *(int*) (PWM_0_ADDR + PWM_PULSE) = pulse_throttle_low; - *(int*) (PWM_1_ADDR + PWM_PULSE) = pulse_throttle_low; - *(int*) (PWM_2_ADDR + PWM_PULSE) = pulse_throttle_low; - *(int*) (PWM_3_ADDR + PWM_PULSE) = pulse_throttle_low; - - usleep(1000000); -} - -/** - * Writes all PWM components to be the same given pulsewidth - */ -void pwm_write_all(int pulseWidth) { - // Check lower and upper bounds - if (pulseWidth > pulse_throttle_high) - pulseWidth = pulse_throttle_high; - if (pulseWidth < pulse_throttle_low) - pulseWidth = pulse_throttle_low; - // Set all the pulse widths - *(int*) (PWM_0_ADDR + PWM_PULSE) = pulseWidth; - *(int*) (PWM_1_ADDR + PWM_PULSE) = pulseWidth; - *(int*) (PWM_2_ADDR + PWM_PULSE) = pulseWidth; - *(int*) (PWM_3_ADDR + PWM_PULSE) = pulseWidth; -} -/** - * Write a given pulseWidth to a channel - */ -void pwm_write_channel(int pulseWidth, int channel){ - // Check lower and upper bounds - if (pulseWidth > pulse_throttle_high) - pulseWidth = pulse_throttle_high; - if (pulseWidth < pulse_throttle_low) - pulseWidth = pulse_throttle_low; - - switch(channel){ - case 0: - *(int*) (PWM_0_ADDR + PWM_PULSE) = pulseWidth; - break; - case 1: - *(int*) (PWM_1_ADDR + PWM_PULSE) = pulseWidth; - break; - case 2: - *(int*) (PWM_2_ADDR + PWM_PULSE) = pulseWidth; - break; - case 3: - *(int*) (PWM_3_ADDR + PWM_PULSE) = pulseWidth; - break; - default: - break; - } -} -/** - * Reads the registers from the PWM_Recorders, and returns the pulse width - * of the last PWM signal to come in - */ -int read_rec(int channel) { - switch (channel) { - case 0: - return *((int*) PWM_REC_0_ADDR); - case 1: - return *((int*) PWM_REC_1_ADDR); - case 2: - return *((int*) PWM_REC_2_ADDR); - case 3: - return *((int*) PWM_REC_3_ADDR); - case 4: - return *((int*) PWM_REC_4_ADDR); - case 5: - return *((int*) PWM_REC_5_ADDR); - default: - return 0; - } -} -/** - * Reads all 4 receiver channels at once - */ -void read_rec_all(int* mixer){ - int i; - for(i = 0; i < 6; i++){ - mixer[i] = read_rec(i); - } -} - -int hexStrToInt(char *buf, int startIdx, int endIdx) { - int result = 0; - int i; - int power = 0; - for (i=endIdx; i >= startIdx; i--) { - int value = buf[i]; - if ('0' <= value && value <= '9') { - value -= '0'; - } else if ('a' <= value && value <= 'f') { - value -= 'a'; - value += 10; - } else if ('A' <= value && value <= 'F') { - value -= 'A'; - value += 10; - } - - result += (2 << (4 * power)) * value; - power++; - } - - return result; -} - -void read_bluetooth_all(int* mixer) { - char buffer[32]; - - int done = 0; - int gotS = 0; - char c = 0; - while (!done) { - int counter = 0; - if (!gotS) { - c = uart0_recvByte(); - } - if (c == 'S') { - - while (1) { - char cc = uart0_recvByte(); - if (cc == 'S') { - counter = 0; - gotS = 1; - break; - } - printf("C=%c,\r\n",cc); - buffer[counter++] = cc; - - - if (counter == 12) { - buffer[12] = 0; - done = 1; - gotS = 0; - } - } - //uart0_recvBytes(buffer, 12); - //buffer[12] = 0; - - - } - } - -// // data := "XX XX XX XX XX" -// uart0_recvBytes(buffer, 12); -// buffer[12] = 0; -// -// - int i; - for(i=0; i < 5; i++) { - mixer[i] = 0; - } - - for (i=0; i < 4; i++) { - //mixer[i] = hexStrToInt(buffer, 3*i, 3*i + 1); - mixer[i] = (buffer[i*3] << 8) | buffer[i*3 + 1]; - } - - printf("mixer: \"%s\" -> %d %d %d %d %d\r\n", buffer, mixer[0], mixer[1], mixer[2], mixer[3], mixer[4]); - -} - -/** - * Use the buttons to drive the pulse length of the channels - */ -void b_drive_pulse() { - int* btns = (int *) XPAR_BTNS_BASEADDR; - - // Increment the pulse width by 5% throttle - if (*btns & 0x1) { - pulseW += 1000; - if (pulseW > 200000) - pulseW = 200000; - pwm_write_all(pulseW); - while (*btns & 0x1) - ; - } //Decrease the pulse width by 5% throttle - else if (*btns & 0x2) { - pulseW -= 1000; - if (pulseW < 100000) { - pulseW = 100000; - } - pwm_write_all(pulseW); - while (*btns & 0x2) - ; - } - // Set the pulses back to default - else if (*btns & 0x4) { - pulseW = MOTOR_0_PERCENT; - pwm_write_all(pulseW); - } - // Read the pulse width of pwm_recorder 0 - else if (*btns & 0x8) { - int i; - for(i = 0; i < 4; i++){ - xil_printf("Channel %d: %d\n", i, read_rec(i)); - } - //xil_printf("%d\n",pulseW); - while (*btns & 0x8) - ; - } -} - -/** - * Creates a sine wave driving the motors from 0 to 100% throttle - */ -void sine_example(){ - - int* btns = (int *) XPAR_BTNS_BASEADDR; - /* Sine Wave */ - static double time = 0; - - time += .0001; - pulseW = (int)fabs(sin(time)*(100000)) + 100000; - //pulseW = (int) (sin(time) + 1)*50000 + 100000; - if (*btns & 0x1){ - printf("%d", pulseW); - printf(" %d\n", *(int*) (PWM_0_ADDR + PWM_PULSE)); - } - pwm_write_all(pulseW); - usleep(300); -} - -void print_mixer(int * mixer){ - int i; - for(i = 0; i < 4; i++){ - xil_printf("%d : %d ", i, mixer[i]); - } - xil_printf("\n"); -} - -/** - * Argument is the reading from the pwm_recorder4 which is connected to the gear pwm - * If the message from the receiver is 0 - gear, kill the system by sending a 1 - * Otherwise, do nothing - */ -int read_kill(int gear){ - if(gear > 115000 && gear < 125000) - return 1; - return 0; -} - -int read_flap(int flap) -{ - // flap '0' is 108,000 CC (Up) - // flap '1' is 192,000 CC (Down) - // here we say if the reading is greater than 150,000 than its '1'; '0' otherwise - if(flap > 150000) - return 1; - return 0; -} - -/** - * Turns off the motors - */ -void pwm_kill(){ - // Initializes the PWM pulse lengths to be 1 ms - *(int*) (PWM_0_ADDR + PWM_PULSE) = pulse_throttle_low; - *(int*) (PWM_1_ADDR + PWM_PULSE) = pulse_throttle_low; - *(int*) (PWM_2_ADDR + PWM_PULSE) = pulse_throttle_low; - *(int*) (PWM_3_ADDR + PWM_PULSE) = pulse_throttle_low; -} - -/** - * Useful stuff in here in regards to PID tuning, and motor tuning - * TODO : Scanf string stuff - * TODO : Make adam do it :DDDDDDDD - */ -void bluetoothTunePID(char instr, gam_t* gam, PID_t* CFpid, PID_t* Gpid){ - int wasX = 0; - int wasPid = 0; - int wasSetpoint = 0; - int wasLog = 0; - char buf[100]; - - switch (instr) { - case 'P': - // Change this if tuning other PIDs - CFpid->Kp += .5; - wasPid = 1; - break; - case 'p': - CFpid->Kp -= .5; - wasPid = 1; - break; - case 'O': - CFpid->Kp += .2; - wasPid = 1; - break; - case 'o': - CFpid->Kp -= .2; - wasPid = 1; - break; - - case 'I': - CFpid->Kp += 0.1; - wasPid = 1; - break; - case 'i': - CFpid->Kp -= 0.1; - wasPid = 1; - break; - case 'W': - Gpid->Kp += 1; - wasPid = 1; - break; - case 'w': - Gpid->Kp -= 1; - wasPid = 1; - break; - case 'E': - Gpid->Kp += 2; - wasPid = 1; - break; - case 'e': - Gpid->Kp -= 2; - wasPid = 1; - break; - case 'R': - Gpid->Kp += 5; - wasPid = 1; - break; - case 'r': - Gpid->Kp -= 5; - wasPid = 1; - break; - case 'D': - CFpid->Kd += .1; - wasPid = 1; - break; - case 'd': - CFpid->Kd -= .1; - wasPid = 1; - break; - case 'S': - CFpid->setpoint += 1; - wasSetpoint = 1; - break; - case 's': - CFpid->setpoint -= 1; - wasSetpoint = 1; - break; - case '0': - motor0_bias += 100; - wasPid = 0; - break; - case '1': - motor1_bias += 100; - wasPid = 0; - break; - case '2': - motor2_bias += 100; - wasPid = 0; - break; - case '3': - motor3_bias += 100; - wasPid = 0; - break; - case ')': - motor0_bias -= 100; - wasPid = 0; - break; - case '!': - motor1_bias -= 100; - wasPid = 0; - break; - case '@': - motor2_bias -= 100; - wasPid = 0; - break; - case '#': - motor3_bias -= 100; - wasPid = 0; - break; - case 'x': - wasX = 1; - break; - case ' ': - wasLog = 1; - break; -/* case 'm': - pid->setpoint = -45.0; - // Change set point - break; - case 'n': - pid->setpoint = 45.0; - */ // Change set point - default: - wasPid = 0; - break; - } - - if(wasX){ - return; - } - else if(wasSetpoint){ - sprintf(buf, "Setpoint: %4.1f\n\r", CFpid->setpoint); - uart0_sendBytes(buf, strlen(buf)); - usleep(5000); - } - else if (wasPid) { - /*sprintf(buf, - "PAngle: %8.3f RAngle: %8.3f PID p: %8.3f d: %8.3f\r\n", - compY, compX, pitchPID.Kp, pitchPID.Kd);*/ - - sprintf(buf, "CFP Coeff: %4.1f D %4.1f GP Coeff: %4.1f\n\r", CFpid->Kp, CFpid->Kd, Gpid->Kp); - uart0_sendBytes(buf, strlen(buf)); - usleep(5000); - } - else if (wasLog){ - sprintf(buf, "CX %5.2f GP GX: %5.2f\n\r", 0.0, gam->gyro_xVel_p); - uart0_sendBytes(buf, strlen(buf)); - usleep(5000); - } - else { - sprintf(buf, "Motor bias's \t\t0: %d 1: %d 2: %d 3: %d \r\n", motor0_bias, - motor1_bias, motor2_bias, motor3_bias); - uart0_sendBytes(buf, strlen(buf)); - -// sprintf(buf, "P: %3.2f I: %3.2f D: %3.2f\r\n", log_struct.ang_vel_pitch_PID_values.P, log_struct.ang_vel_pitch_PID_values.I, log_struct.ang_vel_pitch_PID_values.D); - uart0_sendBytes(buf, strlen(buf)); - usleep(1e4); - } -} -/* -void flash_MIO_7_led(int how_many_times, int ms_between_flashes) -{ - if(how_many_times <= 0) - return; - - while(how_many_times) - { - MIO7_led_on(); - - usleep(ms_between_flashes * 500); - - MIO7_led_off(); - - usleep(ms_between_flashes * 500); - - how_many_times--; - } -} - -void MIO7_led_off() -{ - XGpioPs Gpio; - - XGpioPs_Config * ConfigPtr = XGpioPs_LookupConfig(XPAR_PS7_GPIO_0_DEVICE_ID); - XGpioPs_CfgInitialize(&Gpio, ConfigPtr, ConfigPtr->BaseAddr); - - XGpioPs_SetDirectionPin(&Gpio, 7, 1); - - // Disable LED - XGpioPs_WritePin(&Gpio, 7, 0x00); -} - -void MIO7_led_on() -{ - XGpioPs Gpio; - - XGpioPs_Config * ConfigPtr = XGpioPs_LookupConfig(XPAR_PS7_GPIO_0_DEVICE_ID); - XGpioPs_CfgInitialize(&Gpio, ConfigPtr, ConfigPtr->BaseAddr); - - XGpioPs_SetDirectionPin(&Gpio, 7, 1); - - // Enable LED - XGpioPs_WritePin(&Gpio, 7, 0x01); -} -*/ -void msleep(int msecs) -{ - usleep(msecs * 1000); -} - diff --git a/quad/sw/modular_quad_pid/src/util.h b/quad/sw/modular_quad_pid/src/util.h deleted file mode 100644 index 7c864f4d6ef165749649293280f4630805b89045..0000000000000000000000000000000000000000 --- a/quad/sw/modular_quad_pid/src/util.h +++ /dev/null @@ -1,92 +0,0 @@ -/* - * util.h - * - * Created on: Oct 11, 2014 - * Author: ucart - */ -#ifndef _UTIL_H -#define _UTIL_H - -#include "type_def.h" - - -#define clock_rate 100000000 -#define frequency 450 -#define period_width clock_rate/frequency -#define pulse_throttle_low clock_rate / 1000 // 1ms -#define pulse_throttle_high clock_rate / 500 // 2ms -#define MOTOR_0_PERCENT 115000 - - -#define XPAR_BTNS_BASEADDR 0x41200000 - -/** - * Various Addresses of custom IP components - */ -#define PWM_0_ADDR XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_0_BASEADDR -#define PWM_1_ADDR XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_1_BASEADDR -#define PWM_2_ADDR XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_2_BASEADDR -#define PWM_3_ADDR XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_3_BASEADDR -#define PWM_REC_0_ADDR XPAR_PWM_RECORDER_0_BASEADDR -#define PWM_REC_1_ADDR XPAR_PWM_RECORDER_1_BASEADDR -#define PWM_REC_2_ADDR XPAR_PWM_RECORDER_2_BASEADDR -#define PWM_REC_3_ADDR XPAR_PWM_RECORDER_3_BASEADDR -#define PWM_REC_4_ADDR XPAR_PWM_RECORDER_4_BASEADDR -#define PWM_REC_5_ADDR XPAR_PWM_RECORDER_5_BASEADDR - -/** - * Register offsets within the custom IP - */ -#define PWM_PERIOD 0 -#define PWM_PULSE 4 - -void pwm_init(); -void pwm_write_all(int pulseWidth); -void pwm_write_channel(int pulseWidth, int channel); - -int read_rec(int channel); -void read_rec_all(int* mixer); - -void read_bluetooth_all(int* mixer); - -void b_drive_pulse(); - -void sine_example(); - -void print_mixer(int* mixer); -int read_kill(int gear); -int read_flap(int flap); -void pwm_kill(); - -void printLogging(); -void bluetoothTunePID(char instr, gam_t* gam, PID_t* CFpid, PID_t* Gpid); -void msleep(int msecs); - -/** - * @brief - * Flashes the MIO7 LED how_many_times times and with ms_between_flashes between the flashes. - * - * @param how_many_times - * times the LED should be flashed - * - * @param ms_between_flashes - * time between flashes in milliseconds - * - */ -void flash_MIO_7_led(int how_many_times, int ms_between_flashes); - -/** - * @brief - * Turns off MIO7 LED. - * - */ -void MIO7_led_off(); - -/** - * @brief - * Turns on MIO7 LED. - * - */ -void MIO7_led_on(); - -#endif //_UTIL_H diff --git a/quad/xsdk_workspace/.gitignore b/quad/xsdk_workspace/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..0deb2c3cff4c49e9e7759258b76fa279bc7f381e --- /dev/null +++ b/quad/xsdk_workspace/.gitignore @@ -0,0 +1,8 @@ +SDK.log +test.log +.metadata/ +system_bsp/ps7_cortexa9_0/ +system_bsp/libgen.log +zybo_fsbl_bsp/ps7_cortexa9_0/ +zybo_fsbl_bsp/libgen.log +TAGS \ No newline at end of file diff --git a/quad/sw/README.md b/quad/xsdk_workspace/README.md similarity index 100% rename from quad/sw/README.md rename to quad/xsdk_workspace/README.md diff --git a/quad/sw/imu_logger/.cproject b/quad/xsdk_workspace/imu_logger/.cproject similarity index 100% rename from quad/sw/imu_logger/.cproject rename to quad/xsdk_workspace/imu_logger/.cproject diff --git a/quad/sw/imu_logger/.gitignore b/quad/xsdk_workspace/imu_logger/.gitignore similarity index 100% rename from quad/sw/imu_logger/.gitignore rename to quad/xsdk_workspace/imu_logger/.gitignore diff --git a/quad/sw/imu_logger/.project b/quad/xsdk_workspace/imu_logger/.project similarity index 100% rename from quad/sw/imu_logger/.project rename to quad/xsdk_workspace/imu_logger/.project diff --git a/quad/sw/imu_logger/src/Copy of original lscript.ld b/quad/xsdk_workspace/imu_logger/src/Copy of original lscript.ld similarity index 100% rename from quad/sw/imu_logger/src/Copy of original lscript.ld rename to quad/xsdk_workspace/imu_logger/src/Copy of original lscript.ld diff --git a/quad/sw/modular_quad_pid/src/PID.c b/quad/xsdk_workspace/imu_logger/src/PID.c similarity index 100% rename from quad/sw/modular_quad_pid/src/PID.c rename to quad/xsdk_workspace/imu_logger/src/PID.c diff --git a/quad/sw/imu_logger/src/PID.h b/quad/xsdk_workspace/imu_logger/src/PID.h similarity index 100% rename from quad/sw/imu_logger/src/PID.h rename to quad/xsdk_workspace/imu_logger/src/PID.h diff --git a/quad/sw/modular_quad_pid/src/README.txt b/quad/xsdk_workspace/imu_logger/src/README.txt similarity index 100% rename from quad/sw/modular_quad_pid/src/README.txt rename to quad/xsdk_workspace/imu_logger/src/README.txt diff --git a/quad/sw/imu_logger/src/actuator_command_processing.c b/quad/xsdk_workspace/imu_logger/src/actuator_command_processing.c similarity index 100% rename from quad/sw/imu_logger/src/actuator_command_processing.c rename to quad/xsdk_workspace/imu_logger/src/actuator_command_processing.c diff --git a/quad/sw/modular_quad_pid/src/actuator_command_processing.h b/quad/xsdk_workspace/imu_logger/src/actuator_command_processing.h similarity index 100% rename from quad/sw/modular_quad_pid/src/actuator_command_processing.h rename to quad/xsdk_workspace/imu_logger/src/actuator_command_processing.h diff --git a/quad/sw/imu_logger/src/commands.c b/quad/xsdk_workspace/imu_logger/src/commands.c similarity index 100% rename from quad/sw/imu_logger/src/commands.c rename to quad/xsdk_workspace/imu_logger/src/commands.c diff --git a/quad/sw/imu_logger/src/commands.h b/quad/xsdk_workspace/imu_logger/src/commands.h similarity index 100% rename from quad/sw/imu_logger/src/commands.h rename to quad/xsdk_workspace/imu_logger/src/commands.h diff --git a/quad/sw/imu_logger/src/communication.c b/quad/xsdk_workspace/imu_logger/src/communication.c similarity index 100% rename from quad/sw/imu_logger/src/communication.c rename to quad/xsdk_workspace/imu_logger/src/communication.c diff --git a/quad/sw/imu_logger/src/communication.h b/quad/xsdk_workspace/imu_logger/src/communication.h similarity index 100% rename from quad/sw/imu_logger/src/communication.h rename to quad/xsdk_workspace/imu_logger/src/communication.h diff --git a/quad/sw/imu_logger/src/control_algorithm.c b/quad/xsdk_workspace/imu_logger/src/control_algorithm.c similarity index 100% rename from quad/sw/imu_logger/src/control_algorithm.c rename to quad/xsdk_workspace/imu_logger/src/control_algorithm.c diff --git a/quad/sw/imu_logger/src/control_algorithm.h b/quad/xsdk_workspace/imu_logger/src/control_algorithm.h similarity index 100% rename from quad/sw/imu_logger/src/control_algorithm.h rename to quad/xsdk_workspace/imu_logger/src/control_algorithm.h diff --git a/quad/sw/imu_logger/src/controllers.c b/quad/xsdk_workspace/imu_logger/src/controllers.c similarity index 100% rename from quad/sw/imu_logger/src/controllers.c rename to quad/xsdk_workspace/imu_logger/src/controllers.c diff --git a/quad/sw/modular_quad_pid/src/controllers.h b/quad/xsdk_workspace/imu_logger/src/controllers.h similarity index 100% rename from quad/sw/modular_quad_pid/src/controllers.h rename to quad/xsdk_workspace/imu_logger/src/controllers.h diff --git a/quad/sw/modular_quad_pid/src/conversion.c b/quad/xsdk_workspace/imu_logger/src/conversion.c similarity index 100% rename from quad/sw/modular_quad_pid/src/conversion.c rename to quad/xsdk_workspace/imu_logger/src/conversion.c diff --git a/quad/sw/modular_quad_pid/src/conversion.h b/quad/xsdk_workspace/imu_logger/src/conversion.h similarity index 100% rename from quad/sw/modular_quad_pid/src/conversion.h rename to quad/xsdk_workspace/imu_logger/src/conversion.h diff --git a/quad/sw/imu_logger/src/gam.h b/quad/xsdk_workspace/imu_logger/src/gam.h similarity index 100% rename from quad/sw/imu_logger/src/gam.h rename to quad/xsdk_workspace/imu_logger/src/gam.h diff --git a/quad/sw/imu_logger/src/iic_mpu9150_utils.c b/quad/xsdk_workspace/imu_logger/src/iic_mpu9150_utils.c similarity index 100% rename from quad/sw/imu_logger/src/iic_mpu9150_utils.c rename to quad/xsdk_workspace/imu_logger/src/iic_mpu9150_utils.c diff --git a/quad/sw/imu_logger/src/iic_mpu9150_utils.h b/quad/xsdk_workspace/imu_logger/src/iic_mpu9150_utils.h similarity index 94% rename from quad/sw/imu_logger/src/iic_mpu9150_utils.h rename to quad/xsdk_workspace/imu_logger/src/iic_mpu9150_utils.h index 3c99079338fc1a67259ed140027ac942c53aee85..2ccb8cf394264209c302c29d48cbcb6154c959a9 100644 --- a/quad/sw/imu_logger/src/iic_mpu9150_utils.h +++ b/quad/xsdk_workspace/imu_logger/src/iic_mpu9150_utils.h @@ -15,9 +15,8 @@ #define IIC_MPU9150_UTILS_H -#include "xbasic_types.h" -#include "xiicps.h" #include "type_def.h" +#include "hardware/hw_iface.h" // System configuration registers // (Please see Appendix B: System Level Control Registers in the Zybo TRM) @@ -97,6 +96,8 @@ #define ACCEL_Y_BIAS 0.009f #define ACCEL_Z_BIAS 0.087f +void iic_set_global(struct I2CDriver *given_i2c); + // Initialize hardware; Call this FIRST before calling any other functions int initI2C0(); @@ -134,14 +135,14 @@ void stop_mpu9150(); // Write a byte of data at the given register address on the MPU -void iic0_write(Xuint16 reg_addr, Xuint8 data); +void iic0_write(u16 reg_addr, u8 data); // Read a single byte at a given register address on the MPU -Xuint8 iic0_read(Xuint16 reg_addr); +u8 iic0_read(u16 reg_addr); // Read multiple bytes consecutively at a starting register address // places the resulting bytes in rv -int iic0_read_bytes(Xuint8* rv, Xuint16 reg_addr, int bytes); +int iic0_read_bytes(u8* rv, u16 reg_addr, int bytes); // Helper function to initialize I2C0 controller on the Zybo board // Called by init_iic0 diff --git a/quad/sw/imu_logger/src/initialize_components.c b/quad/xsdk_workspace/imu_logger/src/initialize_components.c similarity index 100% rename from quad/sw/imu_logger/src/initialize_components.c rename to quad/xsdk_workspace/imu_logger/src/initialize_components.c diff --git a/quad/sw/imu_logger/src/initialize_components.h b/quad/xsdk_workspace/imu_logger/src/initialize_components.h similarity index 100% rename from quad/sw/imu_logger/src/initialize_components.h rename to quad/xsdk_workspace/imu_logger/src/initialize_components.h diff --git a/quad/sw/imu_logger/src/log_data.c b/quad/xsdk_workspace/imu_logger/src/log_data.c similarity index 100% rename from quad/sw/imu_logger/src/log_data.c rename to quad/xsdk_workspace/imu_logger/src/log_data.c diff --git a/quad/sw/imu_logger/src/log_data.h b/quad/xsdk_workspace/imu_logger/src/log_data.h similarity index 100% rename from quad/sw/imu_logger/src/log_data.h rename to quad/xsdk_workspace/imu_logger/src/log_data.h diff --git a/quad/sw/modular_quad_pid/src/lscript.ld b/quad/xsdk_workspace/imu_logger/src/lscript.ld similarity index 100% rename from quad/sw/modular_quad_pid/src/lscript.ld rename to quad/xsdk_workspace/imu_logger/src/lscript.ld diff --git a/quad/sw/imu_logger/src/main.c b/quad/xsdk_workspace/imu_logger/src/main.c similarity index 100% rename from quad/sw/imu_logger/src/main.c rename to quad/xsdk_workspace/imu_logger/src/main.c diff --git a/quad/sw/imu_logger/src/mio7_led.c b/quad/xsdk_workspace/imu_logger/src/mio7_led.c similarity index 100% rename from quad/sw/imu_logger/src/mio7_led.c rename to quad/xsdk_workspace/imu_logger/src/mio7_led.c diff --git a/quad/sw/imu_logger/src/mio7_led.h b/quad/xsdk_workspace/imu_logger/src/mio7_led.h similarity index 100% rename from quad/sw/imu_logger/src/mio7_led.h rename to quad/xsdk_workspace/imu_logger/src/mio7_led.h diff --git a/quad/sw/modular_quad_pid/src/new_PID.h b/quad/xsdk_workspace/imu_logger/src/new_PID.h similarity index 100% rename from quad/sw/modular_quad_pid/src/new_PID.h rename to quad/xsdk_workspace/imu_logger/src/new_PID.h diff --git a/quad/sw/modular_quad_pid/src/new_log_data.c b/quad/xsdk_workspace/imu_logger/src/new_log_data.c similarity index 100% rename from quad/sw/modular_quad_pid/src/new_log_data.c rename to quad/xsdk_workspace/imu_logger/src/new_log_data.c diff --git a/quad/sw/imu_logger/src/new_log_data.h b/quad/xsdk_workspace/imu_logger/src/new_log_data.h similarity index 100% rename from quad/sw/imu_logger/src/new_log_data.h rename to quad/xsdk_workspace/imu_logger/src/new_log_data.h diff --git a/quad/sw/imu_logger/src/old_log_data.h b/quad/xsdk_workspace/imu_logger/src/old_log_data.h similarity index 100% rename from quad/sw/imu_logger/src/old_log_data.h rename to quad/xsdk_workspace/imu_logger/src/old_log_data.h diff --git a/quad/sw/imu_logger/src/packet_processing.c b/quad/xsdk_workspace/imu_logger/src/packet_processing.c similarity index 100% rename from quad/sw/imu_logger/src/packet_processing.c rename to quad/xsdk_workspace/imu_logger/src/packet_processing.c diff --git a/quad/sw/modular_quad_pid/src/packet_processing.h b/quad/xsdk_workspace/imu_logger/src/packet_processing.h similarity index 100% rename from quad/sw/modular_quad_pid/src/packet_processing.h rename to quad/xsdk_workspace/imu_logger/src/packet_processing.h diff --git a/quad/sw/imu_logger/src/platform.c b/quad/xsdk_workspace/imu_logger/src/platform.c similarity index 100% rename from quad/sw/imu_logger/src/platform.c rename to quad/xsdk_workspace/imu_logger/src/platform.c diff --git a/quad/sw/imu_logger/src/platform.h b/quad/xsdk_workspace/imu_logger/src/platform.h similarity index 100% rename from quad/sw/imu_logger/src/platform.h rename to quad/xsdk_workspace/imu_logger/src/platform.h diff --git a/quad/sw/imu_logger/src/platform_config.h b/quad/xsdk_workspace/imu_logger/src/platform_config.h similarity index 100% rename from quad/sw/imu_logger/src/platform_config.h rename to quad/xsdk_workspace/imu_logger/src/platform_config.h diff --git a/quad/sw/modular_quad_pid/src/quadposition.h b/quad/xsdk_workspace/imu_logger/src/quadposition.h similarity index 100% rename from quad/sw/modular_quad_pid/src/quadposition.h rename to quad/xsdk_workspace/imu_logger/src/quadposition.h diff --git a/quad/sw/imu_logger/src/send_actuator_commands.c b/quad/xsdk_workspace/imu_logger/src/send_actuator_commands.c similarity index 100% rename from quad/sw/imu_logger/src/send_actuator_commands.c rename to quad/xsdk_workspace/imu_logger/src/send_actuator_commands.c diff --git a/quad/sw/imu_logger/src/send_actuator_commands.h b/quad/xsdk_workspace/imu_logger/src/send_actuator_commands.h similarity index 100% rename from quad/sw/imu_logger/src/send_actuator_commands.h rename to quad/xsdk_workspace/imu_logger/src/send_actuator_commands.h diff --git a/quad/sw/imu_logger/src/sensor.c b/quad/xsdk_workspace/imu_logger/src/sensor.c similarity index 100% rename from quad/sw/imu_logger/src/sensor.c rename to quad/xsdk_workspace/imu_logger/src/sensor.c diff --git a/quad/sw/imu_logger/src/sensor.h b/quad/xsdk_workspace/imu_logger/src/sensor.h similarity index 100% rename from quad/sw/imu_logger/src/sensor.h rename to quad/xsdk_workspace/imu_logger/src/sensor.h diff --git a/quad/sw/imu_logger/src/sensor_processing.c b/quad/xsdk_workspace/imu_logger/src/sensor_processing.c similarity index 100% rename from quad/sw/imu_logger/src/sensor_processing.c rename to quad/xsdk_workspace/imu_logger/src/sensor_processing.c diff --git a/quad/sw/imu_logger/src/sensor_processing.h b/quad/xsdk_workspace/imu_logger/src/sensor_processing.h similarity index 100% rename from quad/sw/imu_logger/src/sensor_processing.h rename to quad/xsdk_workspace/imu_logger/src/sensor_processing.h diff --git a/quad/sw/imu_logger/src/stringBuilder.c b/quad/xsdk_workspace/imu_logger/src/stringBuilder.c similarity index 100% rename from quad/sw/imu_logger/src/stringBuilder.c rename to quad/xsdk_workspace/imu_logger/src/stringBuilder.c diff --git a/quad/sw/imu_logger/src/stringBuilder.h b/quad/xsdk_workspace/imu_logger/src/stringBuilder.h similarity index 100% rename from quad/sw/imu_logger/src/stringBuilder.h rename to quad/xsdk_workspace/imu_logger/src/stringBuilder.h diff --git a/quad/sw/imu_logger/src/timer.c b/quad/xsdk_workspace/imu_logger/src/timer.c similarity index 100% rename from quad/sw/imu_logger/src/timer.c rename to quad/xsdk_workspace/imu_logger/src/timer.c diff --git a/quad/sw/imu_logger/src/timer.h b/quad/xsdk_workspace/imu_logger/src/timer.h similarity index 100% rename from quad/sw/imu_logger/src/timer.h rename to quad/xsdk_workspace/imu_logger/src/timer.h diff --git a/quad/sw/imu_logger/src/type_def.h b/quad/xsdk_workspace/imu_logger/src/type_def.h similarity index 100% rename from quad/sw/imu_logger/src/type_def.h rename to quad/xsdk_workspace/imu_logger/src/type_def.h diff --git a/quad/sw/imu_logger/src/uart.c b/quad/xsdk_workspace/imu_logger/src/uart.c similarity index 100% rename from quad/sw/imu_logger/src/uart.c rename to quad/xsdk_workspace/imu_logger/src/uart.c diff --git a/quad/sw/imu_logger/src/uart.h b/quad/xsdk_workspace/imu_logger/src/uart.h similarity index 100% rename from quad/sw/imu_logger/src/uart.h rename to quad/xsdk_workspace/imu_logger/src/uart.h diff --git a/quad/sw/modular_quad_pid/src/update_gui.c b/quad/xsdk_workspace/imu_logger/src/update_gui.c similarity index 100% rename from quad/sw/modular_quad_pid/src/update_gui.c rename to quad/xsdk_workspace/imu_logger/src/update_gui.c diff --git a/quad/sw/modular_quad_pid/src/update_gui.h b/quad/xsdk_workspace/imu_logger/src/update_gui.h similarity index 100% rename from quad/sw/modular_quad_pid/src/update_gui.h rename to quad/xsdk_workspace/imu_logger/src/update_gui.h diff --git a/quad/sw/imu_logger/src/user_input.c b/quad/xsdk_workspace/imu_logger/src/user_input.c similarity index 100% rename from quad/sw/imu_logger/src/user_input.c rename to quad/xsdk_workspace/imu_logger/src/user_input.c diff --git a/quad/sw/imu_logger/src/user_input.h b/quad/xsdk_workspace/imu_logger/src/user_input.h similarity index 100% rename from quad/sw/imu_logger/src/user_input.h rename to quad/xsdk_workspace/imu_logger/src/user_input.h diff --git a/quad/sw/imu_logger/src/util.c b/quad/xsdk_workspace/imu_logger/src/util.c similarity index 100% rename from quad/sw/imu_logger/src/util.c rename to quad/xsdk_workspace/imu_logger/src/util.c diff --git a/quad/sw/imu_logger/src/util.h b/quad/xsdk_workspace/imu_logger/src/util.h similarity index 100% rename from quad/sw/imu_logger/src/util.h rename to quad/xsdk_workspace/imu_logger/src/util.h diff --git a/quad/sw/modular_quad_pid/.cproject b/quad/xsdk_workspace/modular_quad_pid/.cproject similarity index 91% rename from quad/sw/modular_quad_pid/.cproject rename to quad/xsdk_workspace/modular_quad_pid/.cproject index 2a974bb61e6abb6f71e0b057d0beb3c3c2a5b789..b6594e32f340de9327b789312fb975bd37009524 100644 --- a/quad/sw/modular_quad_pid/.cproject +++ b/quad/xsdk_workspace/modular_quad_pid/.cproject @@ -18,7 +18,7 @@ <storageModule moduleId="cdtBuildSystem" version="4.0.0"> <configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.debug,org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe" cleanCommand="rm -rf" description="" id="xilinx.gnu.arm.exe.debug.980189137" name="Debug" parent="xilinx.gnu.arm.exe.debug"> <folderInfo id="xilinx.gnu.arm.exe.debug.980189137." name="/" resourcePath=""> - <toolChain id="xilinx.gnu.arm.exe.debug.toolchain.1195127676" name="Xilinx ARM GNU Toolchain" superClass="xilinx.gnu.arm.exe.debug.toolchain"> + <toolChain id="xilinx.gnu.arm.exe.debug.toolchain.1195127676" name="Xilinx ARM GNU Toolchain" resourceTypeBasedDiscovery="true" superClass="xilinx.gnu.arm.exe.debug.toolchain"> <targetPlatform binaryParser="com.xilinx.sdk.managedbuilder.XELF.arm" id="xilinx.arm.target.gnu.base.debug.2072264921" isAbstract="false" name="Debug Platform" superClass="xilinx.arm.target.gnu.base.debug"/> <builder buildPath="${workspace_loc:/modular_quad_pid}/Debug" enableAutoBuild="true" id="xilinx.gnu.arm.toolchain.builder.debug.2124876787" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="GNU make" superClass="xilinx.gnu.arm.toolchain.builder.debug"/> <tool id="xilinx.gnu.arm.c.toolchain.assembler.debug.192056667" name="ARM gcc assembler" superClass="xilinx.gnu.arm.c.toolchain.assembler.debug"> @@ -31,6 +31,12 @@ <listOptionValue builtIn="false" value="../../system_bsp/ps7_cortexa9_0/include"/> </option> <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}""/> + </option> <inputType id="xilinx.gnu.arm.c.compiler.input.909725989" name="C source files" superClass="xilinx.gnu.arm.c.compiler.input"/> </tool> <tool id="xilinx.gnu.arm.cxx.toolchain.compiler.debug.1470236349" name="ARM g++ compiler" superClass="xilinx.gnu.arm.cxx.toolchain.compiler.debug"> @@ -52,6 +58,7 @@ <option id="xilinx.gnu.c.link.option.libs.1025826490" name="Libraries (-l)" superClass="xilinx.gnu.c.link.option.libs" valueType="libs"> <listOptionValue builtIn="false" value="m"/> </option> + <option id="xilinx.gnu.c.link.option.paths.1462160427" name="Library search path (-L)" superClass="xilinx.gnu.c.link.option.paths"/> <inputType id="xilinx.gnu.linker.input.777404607" superClass="xilinx.gnu.linker.input"> <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/> <additionalInput kind="additionalinput" paths="$(LIBS)"/> @@ -107,6 +114,12 @@ <option id="xilinx.gnu.compiler.symbols.defined.1562495938" name="Defined symbols (-D)" superClass="xilinx.gnu.compiler.symbols.defined" valueType="definedSymbols"> <listOptionValue builtIn="false" value="NDEBUG=1"/> </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}""/> + </option> <inputType id="xilinx.gnu.arm.c.compiler.input.846429887" name="C source files" superClass="xilinx.gnu.arm.c.compiler.input"/> </tool> <tool id="xilinx.gnu.arm.cxx.toolchain.compiler.release.1846278293" name="ARM g++ compiler" superClass="xilinx.gnu.arm.cxx.toolchain.compiler.release"> @@ -158,6 +171,15 @@ <storageModule moduleId="cdtBuildSystem" version="4.0.0"> <project id="modular_quad_pid.xilinx.gnu.arm.exe.832182557" name="Xilinx ARM Executable" projectType="xilinx.gnu.arm.exe"/> </storageModule> + <storageModule moduleId="refreshScope" versionNumber="2"> + <configuration configurationName="Release"> + <resource resourceType="PROJECT" workspacePath="/modular_quad_pid"/> + </configuration> + <configuration configurationName="Debug"> + <resource resourceType="PROJECT" workspacePath="/modular_quad_pid"/> + </configuration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/> <storageModule moduleId="scannerConfiguration"> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.debug.980189137;xilinx.gnu.arm.exe.debug.980189137."> @@ -166,6 +188,9 @@ <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.release.255973624;xilinx.gnu.arm.exe.release.255973624.;xilinx.gnu.arm.c.toolchain.compiler.release.85270120;xilinx.gnu.arm.c.compiler.input.846429887"> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> </scannerConfigBuildInfo> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.debug.980189137"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> + </scannerConfigBuildInfo> <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.release.255973624;xilinx.gnu.arm.exe.release.255973624."> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> </scannerConfigBuildInfo> @@ -173,13 +198,4 @@ <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> </scannerConfigBuildInfo> </storageModule> - <storageModule moduleId="refreshScope" versionNumber="2"> - <configuration configurationName="Release"> - <resource resourceType="PROJECT" workspacePath="/modular_quad_pid"/> - </configuration> - <configuration configurationName="Debug"> - <resource resourceType="PROJECT" workspacePath="/modular_quad_pid"/> - </configuration> - </storageModule> - <storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/> </cproject> diff --git a/quad/xsdk_workspace/modular_quad_pid/.gitignore b/quad/xsdk_workspace/modular_quad_pid/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..0172c96483ac5bc2da8b0612023c28d29f1c4525 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/.gitignore @@ -0,0 +1,5 @@ +*.o +*.d +*.elf +*.size +bootimage/ diff --git a/quad/xsdk_workspace/modular_quad_pid/.project b/quad/xsdk_workspace/modular_quad_pid/.project new file mode 100644 index 0000000000000000000000000000000000000000..7ae4ca25c0f0cd671784aad1590a7cc52299f7f1 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/.project @@ -0,0 +1,142 @@ +<?xml version="1.0" encoding="UTF-8"?> +<projectDescription> + <name>modular_quad_pid</name> + <comment></comment> + <projects> + <project>system_bsp</project> + <project>system_hw_platform</project> + </projects> + <buildSpec> + <buildCommand> + <name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name> + <arguments> + </arguments> + </buildCommand> + <buildCommand> + <name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name> + <triggers>full,incremental,</triggers> + <arguments> + </arguments> + </buildCommand> + </buildSpec> + <natures> + <nature>org.eclipse.cdt.core.cnature</nature> + <nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature> + <nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature> + </natures> + <linkedResources> + <link> + <name>ext/computation_graph</name> + <type>2</type> + <locationURI>QUAD_LOC/src/computation_graph</locationURI> + </link> + <link> + <name>ext/quad_app</name> + <type>2</type> + <locationURI>QUAD_LOC/src/quad_app</locationURI> + </link> + <link> + <name>ext/queue</name> + <type>2</type> + <locationURI>QUAD_LOC/src/queue</locationURI> + </link> + </linkedResources> + <filteredResources> + <filter> + <id>1489164394345</id> + <name></name> + <type>10</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-obj</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/computation_graph</name> + <type>5</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*.c</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/computation_graph</name> + <type>5</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*.h</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/computation_graph</name> + <type>10</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/quad_app</name> + <type>5</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*.c</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/quad_app</name> + <type>5</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*.h</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/quad_app</name> + <type>10</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/queue</name> + <type>5</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*.c</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/queue</name> + <type>5</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*.h</arguments> + </matcher> + </filter> + <filter> + <id>0</id> + <name>ext/queue</name> + <type>10</type> + <matcher> + <id>org.eclipse.ui.ide.multiFilter</id> + <arguments>1.0-name-matches-false-false-*</arguments> + </matcher> + </filter> + </filteredResources> + <variableList> + <variable> + <name>QUAD_LOC</name> + <value>$%7BPARENT-1-WORKSPACE_LOC%7D</value> + </variable> + </variableList> +</projectDescription> 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 new file mode 100644 index 0000000000000000000000000000000000000000..5ca516e5ff888247e3f9eb3163662686f2e09f4f --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/computation_graph/subdir.mk @@ -0,0 +1,84 @@ +################################################################################ +# 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 \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_accumulator.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_add.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_constant.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_gain.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_mult.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_pow.c + +OBJS += \ +./ext/computation_graph/computation_graph.o \ +./ext/computation_graph/node_accumulator.o \ +./ext/computation_graph/node_add.o \ +./ext/computation_graph/node_constant.o \ +./ext/computation_graph/node_gain.o \ +./ext/computation_graph/node_mult.o \ +./ext/computation_graph/node_pow.o + +C_DEPS += \ +./ext/computation_graph/computation_graph.d \ +./ext/computation_graph/node_accumulator.d \ +./ext/computation_graph/node_add.d \ +./ext/computation_graph/node_constant.d \ +./ext/computation_graph/node_gain.d \ +./ext/computation_graph/node_mult.d \ +./ext/computation_graph/node_pow.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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_accumulator.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_add.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_constant.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_gain.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_mult.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_pow.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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 new file mode 100644 index 0000000000000000000000000000000000000000..aa98b08cd518adce7126a0d547300de93bc0dae8 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/quad_app/subdir.mk @@ -0,0 +1,264 @@ +################################################################################ +# 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/commands.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/node_bounds.c \ +/local/ucart/MicroCART_17-18/quad/src/quad_app/node_mixer.c \ +/local/ucart/MicroCART_17-18/quad/src/quad_app/node_pid.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/commands.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/node_bounds.o \ +./ext/quad_app/node_mixer.o \ +./ext/quad_app/node_pid.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/commands.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/node_bounds.d \ +./ext/quad_app/node_mixer.d \ +./ext/quad_app/node_pid.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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/commands.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/node_bounds.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/node_mixer.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/node_pid.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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 new file mode 100644 index 0000000000000000000000000000000000000000..62a2b5e38e4227b13d52b1f71a3d59ca2c1154a7 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Debug/ext/queue/subdir.mk @@ -0,0 +1,24 @@ +################################################################################ +# 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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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 new file mode 100644 index 0000000000000000000000000000000000000000..1541d5523584e2da44d62a4297e85fb6d6182adf --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Debug/makefile @@ -0,0 +1,61 @@ +################################################################################ +# 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/computation_graph/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 new file mode 100644 index 0000000000000000000000000000000000000000..24a8ef289ae38ceeb8f8ff8531c9bd851e7a09d0 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Debug/objects.mk @@ -0,0 +1,8 @@ +################################################################################ +# 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 new file mode 100644 index 0000000000000000000000000000000000000000..2ab3ec257c3d1145b8c6781b871c0e3a9e1f6f8d --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Debug/sources.mk @@ -0,0 +1,23 @@ +################################################################################ +# 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/computation_graph \ + diff --git a/quad/xsdk_workspace/modular_quad_pid/Debug/src/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Debug/src/subdir.mk new file mode 100644 index 0000000000000000000000000000000000000000..ad5162ebfedbaea78a20e0ab74d85dd782ccb6dc --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Debug/src/subdir.mk @@ -0,0 +1,60 @@ +################################################################################ +# 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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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 new file mode 100644 index 0000000000000000000000000000000000000000..ded259e8facfb900511409b4c0a7bbc52cb3bc30 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Release/ext/computation_graph/subdir.mk @@ -0,0 +1,84 @@ +################################################################################ +# 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 \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_accumulator.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_add.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_constant.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_gain.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_mult.c \ +/local/ucart/MicroCART_17-18/quad/src/computation_graph/node_pow.c + +OBJS += \ +./ext/computation_graph/computation_graph.o \ +./ext/computation_graph/node_accumulator.o \ +./ext/computation_graph/node_add.o \ +./ext/computation_graph/node_constant.o \ +./ext/computation_graph/node_gain.o \ +./ext/computation_graph/node_mult.o \ +./ext/computation_graph/node_pow.o + +C_DEPS += \ +./ext/computation_graph/computation_graph.d \ +./ext/computation_graph/node_accumulator.d \ +./ext/computation_graph/node_add.d \ +./ext/computation_graph/node_constant.d \ +./ext/computation_graph/node_gain.d \ +./ext/computation_graph/node_mult.d \ +./ext/computation_graph/node_pow.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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_accumulator.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_add.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_constant.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_gain.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_mult.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/computation_graph/node_pow.o: /local/ucart/MicroCART_17-18/quad/src/computation_graph/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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 new file mode 100644 index 0000000000000000000000000000000000000000..e98b994aea2b9cb3a2ba124842a4cf5c74226d9e --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Release/ext/quad_app/subdir.mk @@ -0,0 +1,264 @@ +################################################################################ +# 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/commands.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/node_bounds.c \ +/local/ucart/MicroCART_17-18/quad/src/quad_app/node_mixer.c \ +/local/ucart/MicroCART_17-18/quad/src/quad_app/node_pid.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/commands.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/node_bounds.o \ +./ext/quad_app/node_mixer.o \ +./ext/quad_app/node_pid.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/commands.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/node_bounds.d \ +./ext/quad_app/node_mixer.d \ +./ext/quad_app/node_pid.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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/commands.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/node_bounds.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/node_mixer.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +ext/quad_app/node_pid.o: /local/ucart/MicroCART_17-18/quad/src/quad_app/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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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 new file mode 100644 index 0000000000000000000000000000000000000000..f1f9d0801d552b2bcdec436544b890e0720c5f30 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Release/ext/queue/subdir.mk @@ -0,0 +1,24 @@ +################################################################################ +# 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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -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 new file mode 100644 index 0000000000000000000000000000000000000000..1541d5523584e2da44d62a4297e85fb6d6182adf --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Release/makefile @@ -0,0 +1,61 @@ +################################################################################ +# 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/computation_graph/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 new file mode 100644 index 0000000000000000000000000000000000000000..24a8ef289ae38ceeb8f8ff8531c9bd851e7a09d0 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Release/objects.mk @@ -0,0 +1,8 @@ +################################################################################ +# 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 new file mode 100644 index 0000000000000000000000000000000000000000..2ab3ec257c3d1145b8c6781b871c0e3a9e1f6f8d --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Release/sources.mk @@ -0,0 +1,23 @@ +################################################################################ +# 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/computation_graph \ + diff --git a/quad/xsdk_workspace/modular_quad_pid/Release/src/subdir.mk b/quad/xsdk_workspace/modular_quad_pid/Release/src/subdir.mk new file mode 100644 index 0000000000000000000000000000000000000000..1ea77e8c1f87203439ad7a5f60f37e2828a341cc --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/Release/src/subdir.mk @@ -0,0 +1,60 @@ +################################################################################ +# 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" -c -fmessage-length=0 -I../../system_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + + diff --git a/quad/xsdk_workspace/modular_quad_pid/ext/__CAUTION__.md b/quad/xsdk_workspace/modular_quad_pid/ext/__CAUTION__.md new file mode 100644 index 0000000000000000000000000000000000000000..6f7e2a00feb6d7083997b71389dcad6b36a0d616 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/ext/__CAUTION__.md @@ -0,0 +1,12 @@ +**************************************** + Do not edit files in this directory! +**************************************** + +The fine print +---- + +Files in this directory are simlinked to external libraries. They exist here +purely to help fascilitate the build process and permit debugging of those +libraries within XSDK. Editing them here might build within XSDK, but it might +break in its original context. Hence, don't edit these files within XSDK. Edit +them within a workflow that uses the Makefile in the top-level quad folder. diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.c new file mode 100644 index 0000000000000000000000000000000000000000..e8fceffa661ca92e0e1581d291a6f2b07d635819 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.c @@ -0,0 +1,70 @@ +#include "hw_impl_zybo.h" + +struct UARTDriver create_zybo_uart() { + struct UARTDriver uart; + uart.state = NULL; + uart.reset = zybo_uart_reset; + uart.write = zybo_uart_write; + uart.read = zybo_uart_read; + return uart; +} + +struct PWMOutputDriver create_zybo_pwm_outputs() { + struct PWMOutputDriver pwm_outputs; + pwm_outputs.state = NULL; + pwm_outputs.reset = zybo_pwm_output_reset; + pwm_outputs.write = zybo_pwm_output_write; + return pwm_outputs; +} + +struct PWMInputDriver create_zybo_pwm_inputs() { + struct PWMInputDriver pwm_inputs; + pwm_inputs.state = NULL; + pwm_inputs.reset = zybo_pwm_input_reset; + pwm_inputs.read = zybo_pwm_input_read; + return pwm_inputs; +} + +struct I2CDriver create_zybo_i2c() { + struct I2CDriver i2c; + i2c.state = NULL; + i2c.reset = zybo_i2c_reset; + i2c.write = zybo_i2c_write; + i2c.read = zybo_i2c_read; + return i2c; +} + +struct TimerDriver create_zybo_global_timer() { + struct TimerDriver global_timer; + global_timer.state = NULL; + global_timer.reset = zybo_global_timer_reset; + global_timer.restart = zybo_global_timer_restart; + global_timer.read = zybo_global_timer_read; + return global_timer; +} + +struct TimerDriver create_zybo_axi_timer() { + struct TimerDriver axi_timer; + axi_timer.state = NULL; + axi_timer.reset = zybo_axi_timer_reset; + axi_timer.restart = zybo_axi_timer_restart; + axi_timer.read = zybo_axi_timer_read; + return axi_timer; +} + +struct LEDDriver create_zybo_mio7_led() { + struct LEDDriver mio7_led; + mio7_led.state = NULL; + mio7_led.reset = zybo_mio7_led_reset; + mio7_led.turn_on = zybo_mio7_led_turn_on; + mio7_led.turn_off = zybo_mio7_led_turn_off; + return mio7_led; +} + +struct SystemDriver create_zybo_system() { + struct SystemDriver sys; + sys.state = NULL; + sys.reset = zybo_system_reset; + sys.sleep = zybo_system_sleep; + return sys; +} diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.h b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.h new file mode 100644 index 0000000000000000000000000000000000000000..c721307bc08674e414683630564a2f7adf0dd2da --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo.h @@ -0,0 +1,69 @@ +#ifndef HW_IMPL_ZYBO +#define HW_IMPL_ZYBO + +#include "hw_iface.h" + +#include <sleep.h> +#include <stdlib.h> +#include <xtmrctr.h> +#include <xgpiops.h> +#include "xiicps.h" +#include "xparameters.h" +#include "xgpiops.h" +#include "xil_types.h" +#include "xscugic.h" +#include "xtime_l.h" +#include "xuartps.h" +#include "queue.h" +#include "platform.h" +#include "sleep.h" + +int zybo_uart_reset(struct UARTDriver *self); +int zybo_uart_write(struct UARTDriver *self, unsigned char c); +int zybo_uart_read(struct UARTDriver *self, unsigned char *c); + +int zybo_pwm_output_reset(struct PWMOutputDriver *self); +int zybo_pwm_output_write(struct PWMOutputDriver *self, unsigned int channel, unsigned long pulse_width_us); + +int zybo_pwm_input_reset(struct PWMInputDriver *self); +int zybo_pwm_input_read(struct PWMInputDriver *self, unsigned int channel, unsigned long *pulse_width_us); + +int zybo_i2c_reset(struct I2CDriver *self); +int zybo_i2c_write(struct I2CDriver *self, + unsigned short device_addr, + unsigned char *data, + unsigned int length); +int zybo_i2c_read(struct I2CDriver *self, + unsigned short device_addr, + unsigned char *buff, + unsigned int length); + +int zybo_global_timer_reset(struct TimerDriver *self); +int zybo_global_timer_restart(struct TimerDriver *self); +int zybo_global_timer_read(struct TimerDriver *self, u64 *us); + +int zybo_axi_timer_reset(struct TimerDriver *self); +int zybo_axi_timer_restart(struct TimerDriver *self); +int zybo_axi_timer_read(struct TimerDriver *self, u64 *us); + +int zybo_mio7_led_reset(struct LEDDriver *self); +int zybo_mio7_led_turn_on(struct LEDDriver *self); +int zybo_mio7_led_turn_off(struct LEDDriver *self); + +int zybo_system_reset(struct SystemDriver *self); +int zybo_system_sleep(struct SystemDriver *self, unsigned long us); + +struct UARTDriver create_zybo_uart(); +struct PWMOutputDriver create_zybo_pwm_outputs(); +struct PWMInputDriver create_zybo_pwm_inputs(); +struct I2CDriver create_zybo_i2c(); +struct TimerDriver create_zybo_global_timer(); +struct TimerDriver create_zybo_axi_timer(); +struct LEDDriver create_zybo_mio7_led(); +struct SystemDriver create_zybo_system(); + +int test_zybo_i2c(); +int test_zybo_mio7_led_and_system(); +int test_zybo_pwm_inputs(); + +#endif diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_axi_timer.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_axi_timer.c new file mode 100644 index 0000000000000000000000000000000000000000..fa4bb05a6a5bb0bea2167446297a9a29c0b6b9ca --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_axi_timer.c @@ -0,0 +1,22 @@ +#include "hw_impl_zybo.h" + +#define PL_CLK_CNTS_PER_USEC 100 + +int zybo_axi_timer_reset(struct TimerDriver *self) { + if (self->state == NULL) { + self->state = malloc(sizeof(XTmrCtr)); + } + return XTmrCtr_Initialize(self->state, XPAR_AXI_TIMER_0_DEVICE_ID); +} + +int zybo_axi_timer_restart(struct TimerDriver *self) { + XTmrCtr_Reset(self->state, 0); + XTmrCtr_Start(self->state, 0); + return 0; +} + +int zybo_axi_timer_read(struct TimerDriver *self, u64 *us) { + // Returns the number of useconds + *us = XTmrCtr_GetValue(self->state, 0) / PL_CLK_CNTS_PER_USEC; + return 0; +} diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_global_timer.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_global_timer.c new file mode 100644 index 0000000000000000000000000000000000000000..c1024a62f57e9e16eda073268e991012973ec35b --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_global_timer.c @@ -0,0 +1,18 @@ +#include "hw_impl_zybo.h" + +int zybo_global_timer_reset(struct TimerDriver *self) { + // Nothing to initialize + return 0; +} + +int zybo_global_timer_restart(struct TimerDriver *self) { + XTime_SetTime(0); + return 0; +} + +int zybo_global_timer_read(struct TimerDriver *self, u64 *us) { + XTime time; + XTime_GetTime(&time); + *us = ((u64)time * 1000000) / COUNTS_PER_SECOND; // (ticks)(1000000us/s)(s/ticks) + return 0; +} diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_i2c.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_i2c.c new file mode 100644 index 0000000000000000000000000000000000000000..c24a2b7a706db55469e50b56584120a1def9701a --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_i2c.c @@ -0,0 +1,231 @@ +#include "hw_impl_zybo.h" + +#define IO_CLK_CONTROL_REG_ADDR (0xF800012C) + +int XIicPs_MasterSendPolled_ours(XIicPs *InstancePtr, u8 *MsgPtr, + int ByteCount, u16 SlaveAddr); +int XIicPs_SetupMaster(XIicPs *InstancePtr, int Role); + +int zybo_i2c_reset(struct I2CDriver *self) { + if (self->state == NULL) { + self->state = malloc(sizeof(XIicPs)); + } + XIicPs *inst = self->state; + + //Make sure CPU_1x clk is enabled for I2C controller + u16 *aper_ctrl = (u16 *) IO_CLK_CONTROL_REG_ADDR; + + if (*aper_ctrl & 0x00040000){ + xil_printf("CPU_1x is set to I2C0\r\n"); + } + + else { + xil_printf("CPU_1x is not set to I2C0..Setting now\r\n"); + *aper_ctrl |= 0x00040000; + } + + // Look up + XIicPs_Config *i2c_config = XIicPs_LookupConfig(XPAR_PS7_I2C_0_DEVICE_ID); + XStatus status = XIicPs_CfgInitialize(inst, i2c_config, i2c_config->BaseAddress); + + // Check if initialization was successful + if(status != XST_SUCCESS){ + return -1; + } + + // Reset the controller and set the clock to 400kHz + XIicPs_Reset(inst); + XIicPs_SetSClk(inst, 400000); + + return 0; +} + +int zybo_i2c_write(struct I2CDriver *self, + unsigned short device_addr, + unsigned char *data, + unsigned int length) { + XIicPs *inst = self->state; + return XIicPs_MasterSendPolled_ours(inst, data, length, device_addr); +} + +int zybo_i2c_read(struct I2CDriver *self, + unsigned short device_addr, + unsigned char *buff, + unsigned int length) { + XIicPs *inst = self->state; + return XIicPs_MasterRecvPolled(inst, buff, length, device_addr); +} + +/*****************************************************************************/ +/** +* NOTE to MicroCART: This function is originally from the Xilinx library, +* but we noticed that the original function didn't check for a NACK, which +* would cause the original polling function to enter an infinite loop in the +* event of a NACK. Notice that we have added that NACK check at the final +* while loop of this function. +* +* +* This function initiates a polled mode send in master mode. +* +* It sends data to the FIFO and waits for the slave to pick them up. +* If slave fails to remove data from FIFO, the send fails with +* time out. +* +* @param InstancePtr is a pointer to the XIicPs instance. +* @param MsgPtr is the pointer to the send buffer. +* @param ByteCount is the number of bytes to be sent. +* @param SlaveAddr is the address of the slave we are sending to. +* +* @return +* - XST_SUCCESS if everything went well. +* - XST_FAILURE if timed out. +* +* @note This send routine is for polled mode transfer only. +* +****************************************************************************/ +int XIicPs_MasterSendPolled_ours(XIicPs *InstancePtr, u8 *MsgPtr, + int ByteCount, u16 SlaveAddr) +{ + u32 IntrStatusReg; + u32 StatusReg; + u32 BaseAddr; + u32 Intrs; + + /* + * Assert validates the input arguments. + */ + Xil_AssertNonvoid(InstancePtr != NULL); + Xil_AssertNonvoid(MsgPtr != NULL); + Xil_AssertNonvoid(InstancePtr->IsReady == XIL_COMPONENT_IS_READY); + Xil_AssertNonvoid(XIICPS_ADDR_MASK >= SlaveAddr); + + BaseAddr = InstancePtr->Config.BaseAddress; + InstancePtr->SendBufferPtr = MsgPtr; + InstancePtr->SendByteCount = ByteCount; + + XIicPs_SetupMaster(InstancePtr, SENDING_ROLE); + + XIicPs_WriteReg(BaseAddr, XIICPS_ADDR_OFFSET, SlaveAddr); + + /* + * Intrs keeps all the error-related interrupts. + */ + Intrs = XIICPS_IXR_ARB_LOST_MASK | XIICPS_IXR_TX_OVR_MASK | + XIICPS_IXR_TO_MASK | XIICPS_IXR_NACK_MASK; + + /* + * Clear the interrupt status register before use it to monitor. + */ + IntrStatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET); + XIicPs_WriteReg(BaseAddr, XIICPS_ISR_OFFSET, IntrStatusReg); + + /* + * Transmit first FIFO full of data. + */ + TransmitFifoFill(InstancePtr); + + IntrStatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET); + + /* + * Continue sending as long as there is more data and + * there are no errors. + */ + while ((InstancePtr->SendByteCount > 0) && + ((IntrStatusReg & Intrs) == 0)) { + StatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_SR_OFFSET); + + /* + * Wait until transmit FIFO is empty. + */ + if ((StatusReg & XIICPS_SR_TXDV_MASK) != 0) { + IntrStatusReg = XIicPs_ReadReg(BaseAddr, + XIICPS_ISR_OFFSET); + continue; + } + + /* + * Send more data out through transmit FIFO. + */ + TransmitFifoFill(InstancePtr); + } + + /* + * Check for completion of transfer. + */ + // NOTE for MicroCART: Corrected function. Original left for reference. +// while ((XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET) & +// XIICPS_IXR_COMP_MASK) != XIICPS_IXR_COMP_MASK); + while (!(IntrStatusReg & (Intrs | XIICPS_IXR_COMP_MASK))) { + IntrStatusReg = XIicPs_ReadReg(BaseAddr, XIICPS_ISR_OFFSET); + } + + /* + * If there is an error, tell the caller. + */ + if (IntrStatusReg & Intrs) { + return XST_FAILURE; + } + + return XST_SUCCESS; +} + +/*****************************************************************************/ +/* +* NOTE to MicroCART: This function is required by the send polling method above, +* but it was originally static, so we had to copy it word-for-word here. +* +* This function prepares a device to transfers as a master. +* +* @param InstancePtr is a pointer to the XIicPs instance. +* +* @param Role specifies whether the device is sending or receiving. +* +* @return +* - XST_SUCCESS if everything went well. +* - XST_FAILURE if bus is busy. +* +* @note Interrupts are always disabled, device which needs to use +* interrupts needs to setup interrupts after this call. +* +****************************************************************************/ +int XIicPs_SetupMaster(XIicPs *InstancePtr, int Role) +{ + u32 ControlReg; + u32 BaseAddr; + u32 EnabledIntr = 0x0; + + Xil_AssertNonvoid(InstancePtr != NULL); + + BaseAddr = InstancePtr->Config.BaseAddress; + ControlReg = XIicPs_ReadReg(BaseAddr, XIICPS_CR_OFFSET); + + + /* + * Only check if bus is busy when repeated start option is not set. + */ + if ((ControlReg & XIICPS_CR_HOLD_MASK) == 0) { + if (XIicPs_BusIsBusy(InstancePtr)) { + return XST_FAILURE; + } + } + + /* + * Set up master, AckEn, nea and also clear fifo. + */ + ControlReg |= XIICPS_CR_ACKEN_MASK | XIICPS_CR_CLR_FIFO_MASK | + XIICPS_CR_NEA_MASK | XIICPS_CR_MS_MASK; + + if (Role == RECVING_ROLE) { + ControlReg |= XIICPS_CR_RD_WR_MASK; + EnabledIntr = XIICPS_IXR_DATA_MASK |XIICPS_IXR_RX_OVR_MASK; + }else { + ControlReg &= ~XIICPS_CR_RD_WR_MASK; + } + EnabledIntr |= XIICPS_IXR_COMP_MASK | XIICPS_IXR_ARB_LOST_MASK; + + XIicPs_WriteReg(BaseAddr, XIICPS_CR_OFFSET, ControlReg); + + XIicPs_DisableAllInterrupts(BaseAddr); + + return XST_SUCCESS; +} diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_mio7_led.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_mio7_led.c new file mode 100644 index 0000000000000000000000000000000000000000..03a192671114b7e0cbf224b84fbb4c0752bbcd97 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_mio7_led.c @@ -0,0 +1,22 @@ +#include "hw_impl_zybo.h" + +int zybo_mio7_led_reset(struct LEDDriver *self) { + if (self->state == NULL) { + self->state = malloc(sizeof(XGpioPs)); + } + + XGpioPs_Config *ConfigPtr = XGpioPs_LookupConfig(XPAR_PS7_GPIO_0_DEVICE_ID); + XGpioPs_CfgInitialize(self->state, ConfigPtr, ConfigPtr->BaseAddr); + XGpioPs_SetDirectionPin(self->state, 7, 1); + return 0; +} + +int zybo_mio7_led_turn_on(struct LEDDriver *self) { + XGpioPs_WritePin(self->state, 7, 0x01); + return 0; +} + +int zybo_mio7_led_turn_off(struct LEDDriver *self) { + XGpioPs_WritePin(self->state, 7, 0x00); + return 0; +} diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_input.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_input.c new file mode 100644 index 0000000000000000000000000000000000000000..b0c3cd98ef90a33fc0a416f2f02a1ed6b92f57cf --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_input.c @@ -0,0 +1,32 @@ +#include "hw_impl_zybo.h" + +struct PWMInputDriverState { + int *channels[6]; +}; + +int zybo_pwm_input_reset(struct PWMInputDriver *self) { + if (self->state == NULL) { + self->state = malloc(sizeof(struct PWMInputDriverState)); + if (self->state == NULL) { + return -1; + } + } + + // Save the addresses of the input PWM recorders + struct PWMInputDriverState *state = self->state; + state->channels[0] = (int *) XPAR_PWM_RECORDER_0_BASEADDR; + state->channels[1] = (int *) XPAR_PWM_RECORDER_1_BASEADDR; + state->channels[2] = (int *) XPAR_PWM_RECORDER_2_BASEADDR; + state->channels[3] = (int *) XPAR_PWM_RECORDER_3_BASEADDR; + state->channels[4] = (int *) XPAR_PWM_RECORDER_4_BASEADDR; + state->channels[5] = (int *) XPAR_PWM_RECORDER_5_BASEADDR; + return 0; +} + +int zybo_pwm_input_read(struct PWMInputDriver *self, + unsigned int channel, + unsigned long *pulse_width_us) { + struct PWMInputDriverState *state = self->state; + *pulse_width_us = (long) *((int *) state->channels[channel]); + return 0; +} diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_output.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_output.c new file mode 100644 index 0000000000000000000000000000000000000000..3dd09e54379432529a3ce05614dedf648dffb3e2 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_pwm_output.c @@ -0,0 +1,54 @@ +#include "hw_impl_zybo.h" + +#define SYS_CLOCK_RATE 100000000 // ticks per second +#define FREQUENCY 450 +#define PERIOD_WIDTH SYS_CLOCK_RATE/FREQUENCY +#define THROTTLE_PULSE_WIDTH_LOW SYS_CLOCK_RATE/1000 // 1 ms +#define THROTTLE_PULSE_WIDTH_HIGH SYS_CLOCK_RATE/500 // 2 ms +#define PULSE_WIDTH_ADDR_OFFSET 1 + +struct PWMOutputDriverState { + int *outputs[4]; +}; + +int zybo_pwm_output_reset(struct PWMOutputDriver *self) { + if (self->state == NULL) { + self->state = malloc(sizeof(struct PWMOutputDriverState)); + if (self->state == NULL) { + return -1; + } + } + struct PWMOutputDriverState *state = self->state; + + state->outputs[0] = (int *) XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_0_BASEADDR; + state->outputs[1] = (int *) XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_1_BASEADDR; + state->outputs[2] = (int *) XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_2_BASEADDR; + state->outputs[3] = (int *) XPAR_PWM_SIGNAL_OUT_WKILLSWITCH_3_BASEADDR; + + // Set period width of PWM pulse + *(state->outputs[0]) = PERIOD_WIDTH; + *(state->outputs[1]) = PERIOD_WIDTH; + *(state->outputs[2]) = PERIOD_WIDTH; + *(state->outputs[3]) = PERIOD_WIDTH; + + // Set a low pulse (1 ms) so that outputs are off + *(state->outputs[0] + PULSE_WIDTH_ADDR_OFFSET) = THROTTLE_PULSE_WIDTH_LOW; + *(state->outputs[1] + PULSE_WIDTH_ADDR_OFFSET) = THROTTLE_PULSE_WIDTH_LOW; + *(state->outputs[2] + PULSE_WIDTH_ADDR_OFFSET) = THROTTLE_PULSE_WIDTH_LOW; + *(state->outputs[3] + PULSE_WIDTH_ADDR_OFFSET) = THROTTLE_PULSE_WIDTH_LOW; + + usleep(1000000); + return 0; +} + +int zybo_pwm_output_write(struct PWMOutputDriver *self, + unsigned int channel, + unsigned long pulse_width_us) { + if (pulse_width_us > THROTTLE_PULSE_WIDTH_HIGH) + pulse_width_us = THROTTLE_PULSE_WIDTH_HIGH; + if (pulse_width_us < THROTTLE_PULSE_WIDTH_LOW) + pulse_width_us = THROTTLE_PULSE_WIDTH_LOW; + struct PWMOutputDriverState *state = self->state; + *(state->outputs[channel] + PULSE_WIDTH_ADDR_OFFSET) = pulse_width_us; + return 0; +} diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_system.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_system.c new file mode 100644 index 0000000000000000000000000000000000000000..2adcc4007d4891b0f830b58cc03258abf63ef62d --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_system.c @@ -0,0 +1,11 @@ +#include "hw_impl_zybo.h" + +int zybo_system_reset(struct SystemDriver *sys) { + return 0; +} + +int zybo_system_sleep(struct SystemDriver *sys, unsigned long us) { + usleep(us); + return 0; +} + diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_tests.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_tests.c new file mode 100644 index 0000000000000000000000000000000000000000..8fa79cbb283532fed1a65e8c37a80d1c4c489e28 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_tests.c @@ -0,0 +1,258 @@ +#include "hw_impl_zybo.h" +#include "type_def.h" +#include "iic_utils.h" +#include <stdio.h> + +/** + * Test for the LEDDriver and SystemDriver. + * + * This is essentially a basic "blink" program, using the mio7 LED + * on the Zybo board. + * + * Instructions: + * 1) Connect Zybo board to computer by USB cable. + * 2) Set the RUN_TESTS macro in main.c + * 3) Uncomment only this test in main.c + * 4) Run main.c + * 5) Observe MIO7 LED on board blinking at 1 second intervals. + */ +int test_zybo_mio7_led_and_system() { + struct LEDDriver mio7 = create_zybo_mio7_led(); + struct SystemDriver sys = create_zybo_system(); + mio7.reset(&mio7); + sys.reset(&sys); + + while (1) { + mio7.turn_on(&mio7); + sys.sleep(&sys, 1000000); + mio7.turn_off(&mio7); + sys.sleep(&sys, 1000000); + } + + return 0; +} + +/** + * Test for the I2CDriver. + * + * Raw I2C tests are tedius, so we are going to cheat a bit, and use + * some of the LIDAR code we have. + * + * Instructions: + * 1) Connect Zybo Board to computer by USB cable. + * 2) Prepare a breadboard to accomplish the following connections: + * - Zybo GND <-> LIDAR GND + * - Zybo WALL <-> LIDAR VCC + * - Zybo VV5V0 <-> LIDAR VCC + * - Zybo SDA/SCL <-> LIDAR SDA/SCL + * - The Zybo I2C SCL and SDA pins are on pins 1 and 2 of PORT JF, respectively + * 3) Place breakpoint in this test function, somewhere in the while loop. + * 4) Set the RUN_TESTS macro in main.c + * 5) Uncomment only this test in main.c + * 6) Debug main.c + * 7) Step through the while loop, observing x change as you physically change the + * distance of the LIDAR sensor. + */ +int test_zybo_i2c() { + struct I2CDriver i2c = create_zybo_i2c(); + struct SystemDriver sys = create_zybo_system(); + i2c.reset(&i2c); + sys.reset(&sys); + + lidar_t lidar = { }; + iic_set_globals(&i2c, &sys); + if (iic0_lidarlite_init()) return 0; + short x; + while (1) { + iic0_lidarlite_read_distance(&lidar); + x = lidar.distance_cm; + } + return 0; +} + +int test_zybo_i2c_imu() { + struct I2CDriver i2c = create_zybo_i2c(); + struct SystemDriver sys = create_zybo_system(); + i2c.reset(&i2c); + sys.reset(&sys); + + gam_t gam = { }; + iic_set_globals(&i2c, &sys); + if (iic0_mpu9150_start()) return 0; + short x; + while (1) { + iic0_mpu9150_read_gam(&gam); + } + return 0; +} + +/** + * Test for the PWMInputDriver. + * + * Instructions: + * 1) Connect the quad Zybo board to computer using USB. + * 2) Move jumper on Zybo board to use JTAG instead of SD. + * 3) Turn on Zybo board and turn on Spektrum handheld controller. + * - Verify receiver on quad pairs with controller (orange LED should turn on) + * 3) Place breakpoint somewhere in the while loop of this function. + * 4) Set the RUN_TESTS macro in main.c + * 5) Uncomment only this test in main.c + * 6) Debug main. + * 7) Observe the values of pwm_inputs in debugger chaning as you use the + * Spektrum RC controller. + */ +int test_zybo_pwm_inputs() { + struct PWMInputDriver pwm_inputs = create_zybo_pwm_inputs(); + pwm_inputs.reset(&pwm_inputs); + + unsigned long pwms[6]; + while (1) { + int i; + for (i = 0; i < 6; i += 1) { + pwm_inputs.read(&pwm_inputs, i, &pwms[i]); + } + continue; + } +} + +/** + * Test for the PWMOutputDriver. + * + * Instructions: + * 1) Connect the quad Zybo board to computer using USB. + * 2) Move jumper on Zybo board to use JTAG instead of SD. + * 3) Get an oscilloscope and observe PMOD outputs JE7-JE10 + * 4) Set the RUN_TESTS macro in main.c + * 5) Uncomment only this test in main.c + * 6) Run main. + * 7) Observe the PWM width of those PMOD pins changing with time + */ +int test_zybo_pwm_outputs() { + struct PWMOutputDriver pwm_outputs = create_zybo_pwm_outputs(); + pwm_outputs.reset(&pwm_outputs); + struct SystemDriver sys = create_zybo_system(); + sys.reset(&sys); + + while (1) { + int j; + for (j = 100000; j < 200000; j += 1) { + int i; + for (i = 0; i < 4; i += 1) { + pwm_outputs.write(&pwm_outputs, i, j); + sys.sleep(&sys, 50); + } + } + continue; + } + return 0; +} + +/** + * Test for the AXI timer, using LEDDriver. + * + * This is essentially a basic "blink" program, using the mio7 LED + * on the Zybo board. + * + * Instructions: + * 1) Connect Zybo board to computer by USB cable. + * 2) Set the RUN_TESTS macro in main.c + * 3) Uncomment only this test in main.c + * 4) Run main.c + * 5) Observe MIO7 LED on board blinking at 1 second intervals. + */ +int test_zybo_axi_timer() { + struct TimerDriver axi = create_zybo_axi_timer(); + struct LEDDriver led = create_zybo_mio7_led(); + axi.reset(&axi); + led.reset(&led); + + unsigned long time; + + while (1) { + axi.restart(&axi); + time = 0; + while (time < 1000000) { + axi.read(&axi, &time); + } + led.turn_off(&led); + while (time < 2000000) { + axi.read(&axi, &time); + } + led.turn_on(&led); + } +} + +/** + * Test for the Global timer, using LEDDriver. + * + * This is essentially a basic "blink" program, using the mio7 LED + * on the Zybo board. + * + * Instructions: + * 1) Connect Zybo board to computer by USB cable. + * 2) Set the RUN_TESTS macro in main.c + * 3) Uncomment only this test in main.c + * 4) Run main.c + * 5) Observe MIO7 LED on board blinking at 1 second intervals. + */ +int test_zybo_global_timer() { + struct TimerDriver global = create_zybo_global_timer(); + struct LEDDriver led = create_zybo_mio7_led(); + global.reset(&global); + led.reset(&led); + + unsigned long time; + + while (1) { + global.restart(&global); + time = 0; + while (time < 1000000) { + global.read(&global, &time); + } + led.turn_off(&led); + while (time < 2000000) { + global.read(&global, &time); + } + led.turn_on(&led); + } +} + +/** + * Test for the UARTDriver. + * + * Instructions: + * 1) Connect Zybo board to computer by USB cable. + * 2) Get a FTDI Basic Sparkfun board in order to connect the UART pins + * on the Zybo to the computer by USB. + * - Zybo PMOD JC2 (TX) <-> Sparkfun Board RX + * - Zybo PMOD JC3 (RX) <-> sparkfun Board Tx + * - Zybo PMOD JC5 (GND) <-> Sparkfun Board GDN + * 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 + * - Observe test results on terminal + * - You might be able to see LED MIO7 blink when it receives bytes + */ +int test_zybo_uart() { + struct UARTDriver uart = create_zybo_uart(); + struct LEDDriver led = create_zybo_mio7_led(); + uart.reset(&uart); + led.reset(&led); + + unsigned char c; + while (1) { + if (uart.read(&uart, &c)) { + // read failed + led.turn_off(&led); + } else { + // read successful + led.turn_on(&led); + uart.write(&uart, c); + } + } + + return 0; +} + + diff --git a/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_uart.c b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_uart.c new file mode 100644 index 0000000000000000000000000000000000000000..18c17af0a045f70686b001c0de488eacd6efbeaf --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/hw_impl_zybo_uart.c @@ -0,0 +1,286 @@ +#include "hw_impl_zybo.h" + +#define BAUD_RATE 921600 +#define MAX_UART_BUFFER_SIZE 2048 + +int XUartPs_SetBaudRate_ours(XUartPs *InstancePtr, u32 BaudRate); +void uart_interrupt_handler(XUartPs *InstancePtr); +int SetupInterruptSystem(XUartPs *UartInstancePtr, u16 UartIntrId, Xil_ExceptionHandler handler); +void uart_interrupt_handler(XUartPs *InstancePtr); + +// Queue has to be global to be accessible to ISR +static struct Queue queue; +static volatile unsigned char buff[MAX_UART_BUFFER_SIZE]; +static XScuGic xscugic; + +int zybo_uart_reset(struct UARTDriver *self) { + // Instantiate the Driver state + if (self->state == NULL) { + self->state = malloc(sizeof(XUartPs)); + if (self->state == NULL) { + return -1; + } + queue_init(&queue, buff, MAX_UART_BUFFER_SIZE); + } + + XUartPs *inst = self->state;; + + // Configure XUartPs instance + XUartPs_Config* config = XUartPs_LookupConfig(XPAR_PS7_UART_0_DEVICE_ID); + if (XUartPs_CfgInitialize(inst, config, config->BaseAddress) != XST_SUCCESS) { + return -1; + } + + // Set UART Baudrate + if(XUartPs_SetBaudRate_ours(inst, BAUD_RATE) != XST_SUCCESS) { + return -1; + } + + // Clear Tx/Rx FIFOs + int* uart_ctrl_reg = (int*) inst->Config.BaseAddress; + *uart_ctrl_reg |= 0x00000003; // clear TX & RX + + // Setup Interrupts + if (SetupInterruptSystem(inst, XPAR_PS7_UART_0_INTR, (Xil_ExceptionHandler) uart_interrupt_handler) != XST_SUCCESS) { + return -1; + } + + // Interrupts selected: Rx FIFO threashold reached, RX overflow, timeout + u32 IntrMask = XUARTPS_IXR_RXFULL | XUARTPS_IXR_RXOVR | XUARTPS_IXR_TOUT; + XUartPs_SetInterruptMask(inst, IntrMask); + + /* + * Set the receiver timeout. If it is not set, and the last few bytes + * of data do not trigger the over-water or full interrupt, the bytes + * will not be received. By default it is disabled. + * Timeout duration = RecvTimeout x 4 x Bit Period. 0 disables the + * timeout function. + * + * The setting of 8 will timeout after 8 x 4 = 32 character times. + * Increase the time out value if baud rate is high, decrease it if + * baud rate is low. + */ + XUartPs_SetRecvTimeout(inst, 8); + + // Second argument is the number of bytes to trigger an interrupt at + XUartPs_SetFifoThreshold(inst, 48); + + return 0; +} + +int zybo_uart_write(struct UARTDriver *self, unsigned char c) {\ + XUartPs *inst = self->state; + XUartPs_SendByte(inst->Config.BaseAddress, c); + return 0; +} + +int zybo_uart_read(struct UARTDriver *self, unsigned char *c) { + if (queue_remove(&queue, c)) return -1; + else return 0; +} + +//This is copied from xuart driver +/***************************************************/ + +#define XUARTPS_MAX_BAUD_ERROR_RATE 3 /* max % error allowed */ +int XUartPs_SetBaudRate_ours(XUartPs *InstancePtr, u32 BaudRate) +{ + u8 IterBAUDDIV; /* Iterator for available baud divisor values */ + u32 BRGR_Value; /* Calculated value for baud rate generator */ + u32 CalcBaudRate; /* Calculated baud rate */ + u32 BaudError; /* Diff between calculated and requested baud rate */ + u32 Best_BRGR = 0; /* Best value for baud rate generator */ + u8 Best_BAUDDIV = 0; /* Best value for baud divisor */ + u32 Best_Error = 0xFFFFFFFF; + u32 PercentError; + u32 ModeReg; + u32 InputClk; + + /* + * Asserts validate the input arguments + */ + Xil_AssertNonvoid(InstancePtr != NULL); + Xil_AssertNonvoid(InstancePtr->IsReady == XIL_COMPONENT_IS_READY); + //Xil_AssertNonvoid(BaudRate <= XUARTPS_MAX_RATE); + Xil_AssertNonvoid(BaudRate >= XUARTPS_MIN_RATE); + + /* + * Make sure the baud rate is not impossilby large. + * Fastest possible baud rate is Input Clock / 2. + */ + if ((BaudRate * 2) > InstancePtr->Config.InputClockHz) { + return XST_UART_BAUD_ERROR; + } + /* + * Check whether the input clock is divided by 8 + */ + ModeReg = XUartPs_ReadReg( InstancePtr->Config.BaseAddress, + XUARTPS_MR_OFFSET); + + InputClk = InstancePtr->Config.InputClockHz; + if(ModeReg & XUARTPS_MR_CLKSEL) { + InputClk = InstancePtr->Config.InputClockHz / 8; + } + + /* + * Determine the Baud divider. It can be 4to 254. + * Loop through all possible combinations + */ + for (IterBAUDDIV = 4; IterBAUDDIV < 255; IterBAUDDIV++) { + + /* + * Calculate the value for BRGR register + */ + BRGR_Value = InputClk / (BaudRate * (IterBAUDDIV + 1)); + + /* + * Calculate the baud rate from the BRGR value + */ + CalcBaudRate = InputClk/ (BRGR_Value * (IterBAUDDIV + 1)); + + /* + * Avoid unsigned integer underflow + */ + if (BaudRate > CalcBaudRate) { + BaudError = BaudRate - CalcBaudRate; + } + else { + BaudError = CalcBaudRate - BaudRate; + } + + /* + * Find the calculated baud rate closest to requested baud rate. + */ + if (Best_Error > BaudError) { + + Best_BRGR = BRGR_Value; + Best_BAUDDIV = IterBAUDDIV; + Best_Error = BaudError; + } + } + + /* + * Make sure the best error is not too large. + */ + PercentError = (Best_Error * 100) / BaudRate; + if (XUARTPS_MAX_BAUD_ERROR_RATE < PercentError) { + return XST_UART_BAUD_ERROR; + } + + /* + * Disable TX and RX to avoid glitches when setting the baud rate. + */ + XUartPs_DisableUart(InstancePtr); + + XUartPs_WriteReg(InstancePtr->Config.BaseAddress, + XUARTPS_BAUDGEN_OFFSET, Best_BRGR); + XUartPs_WriteReg(InstancePtr->Config.BaseAddress, + XUARTPS_BAUDDIV_OFFSET, Best_BAUDDIV); + + /* + * Enable device + */ + XUartPs_EnableUart(InstancePtr); + + InstancePtr->BaudRate = BaudRate; + + return XST_SUCCESS; + +} + +void uart_interrupt_handler(XUartPs *InstancePtr) { + u32 IsrStatus; + + /* + * Read the interrupt ID register to determine which + * interrupt is active + */ + IsrStatus = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, + XUARTPS_IMR_OFFSET); + + IsrStatus &= XUartPs_ReadReg(InstancePtr->Config.BaseAddress, + XUARTPS_ISR_OFFSET); + + /* + * Read the Channel Status Register to determine if there is any data in + * the RX FIFO + */ + + u32 CsrRegister = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, + XUARTPS_SR_OFFSET); + + while (0 == (CsrRegister & XUARTPS_SR_RXEMPTY)) { + u8 byte = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, XUARTPS_FIFO_OFFSET); + queue_add(&queue, byte); + CsrRegister = XUartPs_ReadReg(InstancePtr->Config.BaseAddress, XUARTPS_SR_OFFSET); + } + + // Clear the interrupt status. + XUartPs_WriteReg(InstancePtr->Config.BaseAddress, XUARTPS_ISR_OFFSET, + IsrStatus); +} + +/*****************************************************************************/ +/** +* +* This function sets up the interrupt system so interrupts can occur for the +* Uart. This function is application-specific. +* +* @param IntcInstancePtr is a pointer to the instance of the INTC. +* @param UartInstancePtr contains a pointer to the instance of the UART +* driver which is going to be connected to the interrupt +* controller. +* @param UartIntrId is the interrupt Id and is typically +* XPAR_<UARTPS_instance>_INTR value from xparameters.h. +* +* @return XST_SUCCESS if successful, otherwise XST_FAILURE. +* +* @note None. +* +****************************************************************************/ +int SetupInterruptSystem(XUartPs *UartInstancePtr, u16 UartIntrId, Xil_ExceptionHandler handler) +{ + int Status; + + XScuGic_Config *IntcConfig; /* Config for interrupt controller */ + + /* Initialize the interrupt controller driver */ + IntcConfig = XScuGic_LookupConfig(XPAR_SCUGIC_SINGLE_DEVICE_ID); + if (NULL == IntcConfig) { + return XST_FAILURE; + } + + Status = XScuGic_CfgInitialize(&xscugic, IntcConfig, + IntcConfig->CpuBaseAddress); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + + /* + * Connect the interrupt controller interrupt handler to the + * hardware interrupt handling logic in the processor. + */ + Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_INT, + (Xil_ExceptionHandler) XScuGic_InterruptHandler, + &xscugic); + + /* + * Connect a device driver handler that will be called when an + * interrupt for the device occurs, the device driver handler + * performs the specific interrupt processing for the device + */ + Status = XScuGic_Connect(&xscugic, UartIntrId, + handler, + (void *) UartInstancePtr); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + + /* Enable the interrupt for the device */ + XScuGic_Enable(&xscugic, UartIntrId); + + /* Enable interrupts */ + Xil_ExceptionEnable(); + + return XST_SUCCESS; +} diff --git a/quad/sw/modular_quad_pid/src/Copy of original lscript.ld b/quad/xsdk_workspace/modular_quad_pid/src/lscript.ld similarity index 98% rename from quad/sw/modular_quad_pid/src/Copy of original lscript.ld rename to quad/xsdk_workspace/modular_quad_pid/src/lscript.ld index 970979a58cb47d318dbc9197e5ceb885993cc867..a9e7524bb4b15ca61a3d8c76f6a001e3b4c86e9f 100644 --- a/quad/sw/modular_quad_pid/src/Copy of original lscript.ld +++ b/quad/xsdk_workspace/modular_quad_pid/src/lscript.ld @@ -10,8 +10,8 @@ /* */ /*******************************************************************/ -_STACK_SIZE = DEFINED(_STACK_SIZE) ? _STACK_SIZE : 0x2000; -_HEAP_SIZE = DEFINED(_HEAP_SIZE) ? _HEAP_SIZE : 0x2000; +_STACK_SIZE = DEFINED(_STACK_SIZE) ? _STACK_SIZE : 0x100000; +_HEAP_SIZE = DEFINED(_HEAP_SIZE) ? _HEAP_SIZE : 0x6400000; _ABORT_STACK_SIZE = DEFINED(_ABORT_STACK_SIZE) ? _ABORT_STACK_SIZE : 1024; _SUPERVISOR_STACK_SIZE = DEFINED(_SUPERVISOR_STACK_SIZE) ? _SUPERVISOR_STACK_SIZE : 2048; diff --git a/quad/xsdk_workspace/modular_quad_pid/src/main.c b/quad/xsdk_workspace/modular_quad_pid/src/main.c new file mode 100644 index 0000000000000000000000000000000000000000..337212a68b5c4829b95de861b9a97f08d4bb93be --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/main.c @@ -0,0 +1,41 @@ +#include <stdio.h> +#include "hw_impl_zybo.h" +#include "quad_app.h" +#include "type_def.h" +#include "platform.h" + +//#define RUN_TESTS + +int setup_hardware(hardware_t *hardware) { + hardware->i2c = create_zybo_i2c(); + hardware->pwm_inputs = create_zybo_pwm_inputs(); + hardware->pwm_outputs = create_zybo_pwm_outputs(); + hardware->uart = create_zybo_uart(); + hardware->global_timer = create_zybo_global_timer(); + hardware->axi_timer = create_zybo_axi_timer(); + hardware->mio7_led = create_zybo_mio7_led(); + hardware->sys = create_zybo_system(); + return 0; +} + +int main() +{ + // Zynq initialization + init_platform(); + +#ifdef RUN_TESTS + //test_zybo_mio7_led_and_system(); + //test_zybo_i2c(); + //test_zybo_i2c_imu(); + //test_zybo_pwm_inputs(); + //test_zybo_pwm_outputs(); + //test_zybo_uart(); + //test_zybo_axi_timer(); + //test_zybo_uart(); + return 0; +#endif + + // Run the main quad application + quad_main(setup_hardware); + return 0; +} diff --git a/quad/sw/modular_quad_pid/src/platform.c b/quad/xsdk_workspace/modular_quad_pid/src/platform.c similarity index 100% rename from quad/sw/modular_quad_pid/src/platform.c rename to quad/xsdk_workspace/modular_quad_pid/src/platform.c diff --git a/quad/sw/modular_quad_pid/src/platform.h b/quad/xsdk_workspace/modular_quad_pid/src/platform.h similarity index 100% rename from quad/sw/modular_quad_pid/src/platform.h rename to quad/xsdk_workspace/modular_quad_pid/src/platform.h diff --git a/quad/sw/modular_quad_pid/src/platform_config.h b/quad/xsdk_workspace/modular_quad_pid/src/platform_config.h similarity index 100% rename from quad/sw/modular_quad_pid/src/platform_config.h rename to quad/xsdk_workspace/modular_quad_pid/src/platform_config.h diff --git a/quad/xsdk_workspace/modular_quad_pid/src/queue.c b/quad/xsdk_workspace/modular_quad_pid/src/queue.c new file mode 120000 index 0000000000000000000000000000000000000000..6b67b81f59670abf26db748c7d699d766c909ae8 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/queue.c @@ -0,0 +1 @@ +../../../../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 new file mode 120000 index 0000000000000000000000000000000000000000..b9524b35495f9ec9badf16668b107d0f72d38556 --- /dev/null +++ b/quad/xsdk_workspace/modular_quad_pid/src/queue.h @@ -0,0 +1 @@ +../../../../lib/queue/queue.h \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/test/.gitignore b/quad/xsdk_workspace/modular_quad_pid/test/.gitignore similarity index 100% rename from quad/sw/modular_quad_pid/test/.gitignore rename to quad/xsdk_workspace/modular_quad_pid/test/.gitignore diff --git a/quad/sw/modular_quad_pid/test/Makefile b/quad/xsdk_workspace/modular_quad_pid/test/Makefile similarity index 100% rename from quad/sw/modular_quad_pid/test/Makefile rename to quad/xsdk_workspace/modular_quad_pid/test/Makefile diff --git a/quad/sw/modular_quad_pid/test/test_uart_buff.c b/quad/xsdk_workspace/modular_quad_pid/test/test_uart_buff.c similarity index 100% rename from quad/sw/modular_quad_pid/test/test_uart_buff.c rename to quad/xsdk_workspace/modular_quad_pid/test/test_uart_buff.c diff --git a/quad/sw/modular_quad_pid/test/xil_types.h b/quad/xsdk_workspace/modular_quad_pid/test/xil_types.h similarity index 100% rename from quad/sw/modular_quad_pid/test/xil_types.h rename to quad/xsdk_workspace/modular_quad_pid/test/xil_types.h diff --git a/quad/xsdk_workspace/system_bsp/.cproject b/quad/xsdk_workspace/system_bsp/.cproject new file mode 100644 index 0000000000000000000000000000000000000000..0e212ccd1591addcefd8a4373b66c277b1bbc84f --- /dev/null +++ b/quad/xsdk_workspace/system_bsp/.cproject @@ -0,0 +1,15 @@ +<?xml version="1.0" encoding="UTF-8" standalone="no"?> +<?fileVersion 4.0.0?> + +<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage"> + <storageModule moduleId="org.eclipse.cdt.core.settings"> + <cconfiguration id="org.eclipse.cdt.core.default.config.1576736349"> + <storageModule buildSystemId="org.eclipse.cdt.core.defaultConfigDataProvider" id="org.eclipse.cdt.core.default.config.1576736349" moduleId="org.eclipse.cdt.core.settings" name="Configuration"> + <externalSettings/> + <extensions/> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> + </cconfiguration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/> +</cproject> diff --git a/quad/xsdk_workspace/system_bsp/.project b/quad/xsdk_workspace/system_bsp/.project new file mode 100644 index 0000000000000000000000000000000000000000..922cddb11b529d10df5598fa8248359e0be5db72 --- /dev/null +++ b/quad/xsdk_workspace/system_bsp/.project @@ -0,0 +1,76 @@ +<?xml version="1.0" encoding="UTF-8"?> +<projectDescription> + <name>system_bsp</name> + <comment></comment> + <projects> + <project>system_hw_platform</project> + </projects> + <buildSpec> + <buildCommand> + <name>org.eclipse.cdt.make.core.makeBuilder</name> + <arguments> + <dictionary> + <key>org.eclipse.cdt.core.errorOutputParser</key> + <value>org.eclipse.cdt.core.GASErrorParser;org.eclipse.cdt.core.GCCErrorParser;org.eclipse.cdt.core.GLDErrorParser;org.eclipse.cdt.core.GmakeErrorParser;org.eclipse.cdt.core.VCErrorParser;org.eclipse.cdt.core.CWDLocator;org.eclipse.cdt.core.MakeErrorParser;</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.append_environment</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.arguments</key> + <value></value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.command</key> + <value>make</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.target.auto</key> + <value>all</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.target.clean</key> + <value>clean</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.target.inc</key> + <value>all</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enableAutoBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enableCleanBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enableFullBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enabledIncrementalBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.environment</key> + <value></value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.stopOnError</key> + <value>false</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key> + <value>true</value> + </dictionary> + </arguments> + </buildCommand> + </buildSpec> + <natures> + <nature>com.xilinx.sdk.sw.SwProjectNature</nature> + <nature>org.eclipse.cdt.core.cnature</nature> + <nature>org.eclipse.cdt.make.core.makeNature</nature> + </natures> +</projectDescription> diff --git a/quad/xsdk_workspace/system_bsp/.sdkproject b/quad/xsdk_workspace/system_bsp/.sdkproject new file mode 100644 index 0000000000000000000000000000000000000000..3135ec9f796f86108f3510421221835514fcc15f --- /dev/null +++ b/quad/xsdk_workspace/system_bsp/.sdkproject @@ -0,0 +1,3 @@ +THIRPARTY=false +PROCESSOR=ps7_cortexa9_0 +MSS_FILE=system.mss diff --git a/quad/xsdk_workspace/system_bsp/Makefile b/quad/xsdk_workspace/system_bsp/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..fe2a0efc7cc39ff9edfdbb9064b229a72106cb58 --- /dev/null +++ b/quad/xsdk_workspace/system_bsp/Makefile @@ -0,0 +1,21 @@ +# Makefile generated by Xilinx SDK. + +-include libgen.options + +LIBRARIES = ${PROCESSOR}/lib/libxil.a +MSS = system.mss + +all: libs + @echo 'Finished building libraries' + +libs: $(LIBRARIES) + +$(LIBRARIES): $(MSS) + libgen -hw ${HWSPEC}\ + ${REPOSITORIES}\ + -pe ${PROCESSOR} \ + -log libgen.log \ + $(MSS) + +clean: + rm -rf ${PROCESSOR} diff --git a/quad/xsdk_workspace/system_bsp/libgen.options b/quad/xsdk_workspace/system_bsp/libgen.options new file mode 100644 index 0000000000000000000000000000000000000000..ac5ba396687b73316827155661d71b9247b953be --- /dev/null +++ b/quad/xsdk_workspace/system_bsp/libgen.options @@ -0,0 +1,3 @@ +PROCESSOR=ps7_cortexa9_0 +REPOSITORIES= +HWSPEC=../system_hw_platform/system.xml diff --git a/quad/xsdk_workspace/system_bsp/system.mss b/quad/xsdk_workspace/system_bsp/system.mss new file mode 100644 index 0000000000000000000000000000000000000000..ceb921a9ac033db1e420df4bdfd1997b061f6f83 --- /dev/null +++ b/quad/xsdk_workspace/system_bsp/system.mss @@ -0,0 +1,291 @@ + + PARAMETER VERSION = 2.2.0 + + +BEGIN OS + PARAMETER OS_NAME = standalone + PARAMETER OS_VER = 3.11.a + PARAMETER PROC_INSTANCE = ps7_cortexa9_0 + PARAMETER STDIN = ps7_uart_1 + PARAMETER STDOUT = ps7_uart_1 +END + + +BEGIN PROCESSOR + PARAMETER DRIVER_NAME = cpu_cortexa9 + PARAMETER DRIVER_VER = 1.01.a + PARAMETER HW_INSTANCE = ps7_cortexa9_0 +END + + +BEGIN DRIVER + PARAMETER DRIVER_NAME = tmrctr + PARAMETER DRIVER_VER = 2.05.a + PARAMETER HW_INSTANCE = axi_timer_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = gpio + PARAMETER DRIVER_VER = 3.01.a + PARAMETER HW_INSTANCE = btns_4bits_tri_io +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_2 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_3 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_coresight_comp_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ddr_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ddrc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = devcfg + PARAMETER DRIVER_VER = 2.04.a + PARAMETER HW_INSTANCE = ps7_dev_cfg_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = dmaps + PARAMETER DRIVER_VER = 1.06.a + PARAMETER HW_INSTANCE = ps7_dma_ns +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = dmaps + PARAMETER DRIVER_VER = 1.06.a + PARAMETER HW_INSTANCE = ps7_dma_s +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = emacps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_ethernet_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_globaltimer_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = gpiops + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_gpio_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_gpv_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = iicps + PARAMETER DRIVER_VER = 1.04.a + PARAMETER HW_INSTANCE = ps7_i2c_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_intc_dist_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_iop_bus_config_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_l2cachec_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ocmc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = qspips + PARAMETER DRIVER_VER = 2.03.a + PARAMETER HW_INSTANCE = ps7_qspi_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_qspi_linear_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ram_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ram_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_scuc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = scugic + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_scugic_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = scutimer + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_scutimer_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = scuwdt + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_scuwdt_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_sd_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_slcr_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = uartps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_uart_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = uartps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_uart_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = usbps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_usb_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = xadcps + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_xadc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_2 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_3 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_4 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_5 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_2 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_3 +END + + diff --git a/quad/sw/system_hw_platform/.project b/quad/xsdk_workspace/system_hw_platform/.project similarity index 100% rename from quad/sw/system_hw_platform/.project rename to quad/xsdk_workspace/system_hw_platform/.project diff --git a/quad/sw/system_hw_platform/ps7_init.c b/quad/xsdk_workspace/system_hw_platform/ps7_init.c similarity index 100% rename from quad/sw/system_hw_platform/ps7_init.c rename to quad/xsdk_workspace/system_hw_platform/ps7_init.c diff --git a/quad/sw/system_hw_platform/ps7_init.h b/quad/xsdk_workspace/system_hw_platform/ps7_init.h similarity index 100% rename from quad/sw/system_hw_platform/ps7_init.h rename to quad/xsdk_workspace/system_hw_platform/ps7_init.h diff --git a/quad/sw/system_hw_platform/ps7_init.html b/quad/xsdk_workspace/system_hw_platform/ps7_init.html similarity index 100% rename from quad/sw/system_hw_platform/ps7_init.html rename to quad/xsdk_workspace/system_hw_platform/ps7_init.html diff --git a/quad/sw/system_hw_platform/ps7_init.tcl b/quad/xsdk_workspace/system_hw_platform/ps7_init.tcl similarity index 100% rename from quad/sw/system_hw_platform/ps7_init.tcl rename to quad/xsdk_workspace/system_hw_platform/ps7_init.tcl diff --git a/quad/sw/system_hw_platform/system.bit b/quad/xsdk_workspace/system_hw_platform/system.bit similarity index 100% rename from quad/sw/system_hw_platform/system.bit rename to quad/xsdk_workspace/system_hw_platform/system.bit diff --git a/quad/sw/system_hw_platform/system.xml b/quad/xsdk_workspace/system_hw_platform/system.xml similarity index 100% rename from quad/sw/system_hw_platform/system.xml rename to quad/xsdk_workspace/system_hw_platform/system.xml diff --git a/quad/xsdk_workspace/zybo_fsbl/.cproject b/quad/xsdk_workspace/zybo_fsbl/.cproject new file mode 100644 index 0000000000000000000000000000000000000000..8047c604215d0cda99d40a39a7af8fbd78ca1e16 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/.cproject @@ -0,0 +1,172 @@ +<?xml version="1.0" encoding="UTF-8" standalone="no"?> +<?fileVersion 4.0.0?> + +<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage"> + <storageModule moduleId="org.eclipse.cdt.core.settings"> + <cconfiguration id="xilinx.gnu.arm.exe.debug.563267343"> + <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="xilinx.gnu.arm.exe.debug.563267343" moduleId="org.eclipse.cdt.core.settings" name="Debug"> + <externalSettings/> + <extensions> + <extension id="com.xilinx.sdk.managedbuilder.XELF.arm" point="org.eclipse.cdt.core.BinaryParser"/> + <extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + </extensions> + </storageModule> + <storageModule moduleId="cdtBuildSystem" version="4.0.0"> + <configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.debug,org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe" cleanCommand="rm -rf" description="" id="xilinx.gnu.arm.exe.debug.563267343" name="Debug" parent="xilinx.gnu.arm.exe.debug"> + <folderInfo id="xilinx.gnu.arm.exe.debug.563267343." name="/" resourcePath=""> + <toolChain id="xilinx.gnu.arm.exe.debug.toolchain.1310213535" name="Xilinx ARM GNU Toolchain" superClass="xilinx.gnu.arm.exe.debug.toolchain"> + <targetPlatform binaryParser="com.xilinx.sdk.managedbuilder.XELF.arm" id="xilinx.arm.target.gnu.base.debug.920830407" isAbstract="false" name="Debug Platform" superClass="xilinx.arm.target.gnu.base.debug"/> + <builder buildPath="${workspace_loc:/zybo_fsbl}/Debug" enableAutoBuild="true" id="xilinx.gnu.arm.toolchain.builder.debug.454763412" managedBuildOn="true" name="GNU make.Debug" superClass="xilinx.gnu.arm.toolchain.builder.debug"/> + <tool id="xilinx.gnu.arm.c.toolchain.assembler.debug.1540227256" name="ARM gcc assembler" superClass="xilinx.gnu.arm.c.toolchain.assembler.debug"> + <inputType id="xilinx.gnu.assembler.input.13485298" superClass="xilinx.gnu.assembler.input"/> + </tool> + <tool id="xilinx.gnu.arm.c.toolchain.compiler.debug.457673602" 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.411922602" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.1888303961" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.max" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.780971215" superClass="xilinx.gnu.compiler.inferred.swplatform.includes" valueType="includePath"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/include"/> + </option> + <inputType id="xilinx.gnu.arm.c.compiler.input.940838417" name="C source files" superClass="xilinx.gnu.arm.c.compiler.input"/> + </tool> + <tool id="xilinx.gnu.arm.cxx.toolchain.compiler.debug.1067895073" name="ARM g++ compiler" superClass="xilinx.gnu.arm.cxx.toolchain.compiler.debug"> + <option defaultValue="gnu.c.optimization.level.none" id="xilinx.gnu.compiler.option.optimization.level.208739742" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.623682590" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.max" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.1087976457" superClass="xilinx.gnu.compiler.inferred.swplatform.includes" valueType="includePath"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/include"/> + </option> + </tool> + <tool id="xilinx.gnu.arm.toolchain.archiver.1485154551" name="ARM archiver" superClass="xilinx.gnu.arm.toolchain.archiver"/> + <tool id="xilinx.gnu.arm.c.toolchain.linker.debug.694524981" name="ARM gcc linker" superClass="xilinx.gnu.arm.c.toolchain.linker.debug"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.555585521" superClass="xilinx.gnu.linker.inferred.swplatform.lpath" valueType="libPaths"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/lib"/> + </option> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.325777166" superClass="xilinx.gnu.linker.inferred.swplatform.flags" valueType="libs"> + <listOptionValue builtIn="false" value="-Wl,--start-group,-lxil,-lgcc,-lc,--end-group"/> + </option> + <option id="xilinx.gnu.c.linker.option.lscript.704335692" superClass="xilinx.gnu.c.linker.option.lscript" value="../src/lscript.ld" valueType="string"/> + <option id="xilinx.gnu.c.link.option.libs.828267603" superClass="xilinx.gnu.c.link.option.libs" valueType="libs"> + <listOptionValue builtIn="false" value="rsa"/> + </option> + <option id="xilinx.gnu.c.link.option.paths.2031068232" superClass="xilinx.gnu.c.link.option.paths" valueType="libPaths"> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src}""/> + </option> + <inputType id="xilinx.gnu.linker.input.1097085627" superClass="xilinx.gnu.linker.input"> + <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/> + <additionalInput kind="additionalinput" paths="$(LIBS)"/> + </inputType> + <inputType id="xilinx.gnu.linker.input.lscript.1428414389" name="Linker Script" superClass="xilinx.gnu.linker.input.lscript"/> + </tool> + <tool id="xilinx.gnu.arm.cxx.toolchain.linker.debug.1114403279" name="ARM g++ linker" superClass="xilinx.gnu.arm.cxx.toolchain.linker.debug"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.721160155" superClass="xilinx.gnu.linker.inferred.swplatform.lpath" valueType="libPaths"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/lib"/> + </option> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.2127848659" superClass="xilinx.gnu.linker.inferred.swplatform.flags" valueType="libs"> + <listOptionValue builtIn="false" value="-Wl,--start-group,-lxil,-lgcc,-lc,--end-group"/> + </option> + <option id="xilinx.gnu.c.linker.option.lscript.1094205127" superClass="xilinx.gnu.c.linker.option.lscript" value="../src/lscript.ld" valueType="string"/> + </tool> + <tool id="xilinx.gnu.arm.size.debug.140413066" name="ARM Print Size" superClass="xilinx.gnu.arm.size.debug"/> + </toolChain> + </folderInfo> + </configuration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> + </cconfiguration> + <cconfiguration id="xilinx.gnu.arm.exe.release.876704639"> + <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="xilinx.gnu.arm.exe.release.876704639" moduleId="org.eclipse.cdt.core.settings" name="Release"> + <externalSettings/> + <extensions> + <extension id="com.xilinx.sdk.managedbuilder.XELF.arm" point="org.eclipse.cdt.core.BinaryParser"/> + <extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + </extensions> + </storageModule> + <storageModule moduleId="cdtBuildSystem" version="4.0.0"> + <configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release,org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe" cleanCommand="rm -rf" description="" id="xilinx.gnu.arm.exe.release.876704639" name="Release" parent="xilinx.gnu.arm.exe.release"> + <folderInfo id="xilinx.gnu.arm.exe.release.876704639." name="/" resourcePath=""> + <toolChain id="xilinx.gnu.arm.exe.release.toolchain.1830653593" name="Xilinx ARM GNU Toolchain" superClass="xilinx.gnu.arm.exe.release.toolchain"> + <targetPlatform binaryParser="com.xilinx.sdk.managedbuilder.XELF.arm" id="xilinx.arm.target.gnu.base.release.1084312672" isAbstract="false" name="Release Platform" superClass="xilinx.arm.target.gnu.base.release"/> + <builder buildPath="${workspace_loc:/zybo_fsbl}/Release" enableAutoBuild="true" id="xilinx.gnu.arm.toolchain.builder.release.1683299044" managedBuildOn="true" name="GNU make.Release" superClass="xilinx.gnu.arm.toolchain.builder.release"/> + <tool id="xilinx.gnu.arm.c.toolchain.assembler.release.1080212411" name="ARM gcc assembler" superClass="xilinx.gnu.arm.c.toolchain.assembler.release"> + <inputType id="xilinx.gnu.assembler.input.1832895311" superClass="xilinx.gnu.assembler.input"/> + </tool> + <tool id="xilinx.gnu.arm.c.toolchain.compiler.release.791004764" name="ARM gcc compiler" superClass="xilinx.gnu.arm.c.toolchain.compiler.release"> + <option defaultValue="gnu.c.optimization.level.more" id="xilinx.gnu.compiler.option.optimization.level.559747089" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.878012378" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.none" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.1232059953" superClass="xilinx.gnu.compiler.inferred.swplatform.includes" valueType="includePath"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/include"/> + </option> + <inputType id="xilinx.gnu.arm.c.compiler.input.1024044361" name="C source files" superClass="xilinx.gnu.arm.c.compiler.input"/> + </tool> + <tool id="xilinx.gnu.arm.cxx.toolchain.compiler.release.876683390" name="ARM g++ compiler" superClass="xilinx.gnu.arm.cxx.toolchain.compiler.release"> + <option defaultValue="gnu.c.optimization.level.more" id="xilinx.gnu.compiler.option.optimization.level.20716866" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.1356264316" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.none" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.600073042" superClass="xilinx.gnu.compiler.inferred.swplatform.includes" valueType="includePath"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/include"/> + </option> + </tool> + <tool id="xilinx.gnu.arm.toolchain.archiver.1706567348" name="ARM archiver" superClass="xilinx.gnu.arm.toolchain.archiver"/> + <tool id="xilinx.gnu.arm.c.toolchain.linker.release.1064703959" name="ARM gcc linker" superClass="xilinx.gnu.arm.c.toolchain.linker.release"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.2100658751" superClass="xilinx.gnu.linker.inferred.swplatform.lpath" valueType="libPaths"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/lib"/> + </option> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.332840161" superClass="xilinx.gnu.linker.inferred.swplatform.flags" valueType="libs"> + <listOptionValue builtIn="false" value="-Wl,--start-group,-lxil,-lgcc,-lc,--end-group"/> + </option> + <option id="xilinx.gnu.c.linker.option.lscript.1461998249" superClass="xilinx.gnu.c.linker.option.lscript" value="../src/lscript.ld" valueType="string"/> + <option id="xilinx.gnu.c.link.option.libs.1570584843" superClass="xilinx.gnu.c.link.option.libs" valueType="libs"> + <listOptionValue builtIn="false" value="rsa"/> + </option> + <option id="xilinx.gnu.c.link.option.paths.304586361" superClass="xilinx.gnu.c.link.option.paths" valueType="libPaths"> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src}""/> + </option> + <inputType id="xilinx.gnu.linker.input.568924798" superClass="xilinx.gnu.linker.input"> + <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/> + <additionalInput kind="additionalinput" paths="$(LIBS)"/> + </inputType> + <inputType id="xilinx.gnu.linker.input.lscript.78755099" name="Linker Script" superClass="xilinx.gnu.linker.input.lscript"/> + </tool> + <tool id="xilinx.gnu.arm.cxx.toolchain.linker.release.195782372" name="ARM g++ linker" superClass="xilinx.gnu.arm.cxx.toolchain.linker.release"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.745005125" superClass="xilinx.gnu.linker.inferred.swplatform.lpath" valueType="libPaths"> + <listOptionValue builtIn="false" value="../../zybo_fsbl_bsp/ps7_cortexa9_0/lib"/> + </option> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.1911791627" superClass="xilinx.gnu.linker.inferred.swplatform.flags" valueType="libs"> + <listOptionValue builtIn="false" value="-Wl,--start-group,-lxil,-lgcc,-lc,--end-group"/> + </option> + <option id="xilinx.gnu.c.linker.option.lscript.1735659922" superClass="xilinx.gnu.c.linker.option.lscript" value="../src/lscript.ld" valueType="string"/> + </tool> + <tool id="xilinx.gnu.arm.size.release.1178224723" name="ARM Print Size" superClass="xilinx.gnu.arm.size.release"/> + </toolChain> + </folderInfo> + </configuration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> + </cconfiguration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/> + <storageModule moduleId="cdtBuildSystem" version="4.0.0"> + <project id="zybo_fsbl.xilinx.gnu.arm.exe.2046878906" name="Xilinx ARM Executable" projectType="xilinx.gnu.arm.exe"/> + </storageModule> + <storageModule moduleId="scannerConfiguration"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.release.876704639;xilinx.gnu.arm.exe.release.876704639.;xilinx.gnu.arm.c.toolchain.compiler.release.791004764;xilinx.gnu.arm.c.compiler.input.1024044361"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> + </scannerConfigBuildInfo> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.debug.563267343;xilinx.gnu.arm.exe.debug.563267343.;xilinx.gnu.arm.c.toolchain.compiler.debug.457673602;xilinx.gnu.arm.c.compiler.input.940838417"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> + </scannerConfigBuildInfo> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.debug.563267343;xilinx.gnu.arm.exe.debug.563267343."> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> + </scannerConfigBuildInfo> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.release.876704639;xilinx.gnu.arm.exe.release.876704639."> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> + </scannerConfigBuildInfo> + </storageModule> +</cproject> diff --git a/quad/xsdk_workspace/zybo_fsbl/.gitignore b/quad/xsdk_workspace/zybo_fsbl/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..a92e1611ddfdb7685cb2660245489c5bfdea3494 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/.gitignore @@ -0,0 +1,5 @@ +*.o +*.d +*.elf +*.size +bootimage/ \ No newline at end of file diff --git a/quad/sw/modular_quad_pid/.project b/quad/xsdk_workspace/zybo_fsbl/.project similarity index 84% rename from quad/sw/modular_quad_pid/.project rename to quad/xsdk_workspace/zybo_fsbl/.project index bb5f1cfda9ec5d0ae27231be921b55d9fed41736..bc2d382197a84b9721fcff26d44f304f29f1d097 100644 --- a/quad/sw/modular_quad_pid/.project +++ b/quad/xsdk_workspace/zybo_fsbl/.project @@ -1,10 +1,9 @@ <?xml version="1.0" encoding="UTF-8"?> <projectDescription> - <name>modular_quad_pid</name> - <comment></comment> + <name>zybo_fsbl</name> + <comment>zybo_fsbl_bsp - ps7_cortexa9_0</comment> <projects> - <project>system_bsp_new</project> - <project>system_bsp</project> + <project>zybo_fsbl_bsp</project> </projects> <buildSpec> <buildCommand> diff --git a/quad/xsdk_workspace/zybo_fsbl/Debug/makefile b/quad/xsdk_workspace/zybo_fsbl/Debug/makefile new file mode 100644 index 0000000000000000000000000000000000000000..97959e1ede4a1a3378f2241945e4d9dc184546ac --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Debug/makefile @@ -0,0 +1,58 @@ +################################################################################ +# 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 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 += \ +zybo_fsbl.elf.size \ + + +# All Target +all: zybo_fsbl.elf secondary-outputs + +# Tool invocations +zybo_fsbl.elf: $(OBJS) ../src/lscript.ld $(USER_OBJS) + @echo 'Building target: $@' + @echo 'Invoking: ARM gcc linker' + arm-xilinx-eabi-gcc -L"/local/ucart/MicroCART_17-18/quad/xsdk_workspace/zybo_fsbl/src" -Wl,-T -Wl,../src/lscript.ld -L../../zybo_fsbl_bsp/ps7_cortexa9_0/lib -o "zybo_fsbl.elf" $(OBJS) $(USER_OBJS) $(LIBS) + @echo 'Finished building target: $@' + @echo ' ' + +zybo_fsbl.elf.size: zybo_fsbl.elf + @echo 'Invoking: ARM Print Size' + arm-xilinx-eabi-size zybo_fsbl.elf |tee "zybo_fsbl.elf.size" + @echo 'Finished building: $@' + @echo ' ' + +# Other Targets +clean: + -$(RM) $(OBJS)$(C_DEPS)$(EXECUTABLES)$(ELFSIZE)$(S_UPPER_DEPS) zybo_fsbl.elf + -@echo ' ' + +secondary-outputs: $(ELFSIZE) + +.PHONY: all clean dependents +.SECONDARY: + +-include ../makefile.targets diff --git a/quad/xsdk_workspace/zybo_fsbl/Debug/objects.mk b/quad/xsdk_workspace/zybo_fsbl/Debug/objects.mk new file mode 100644 index 0000000000000000000000000000000000000000..88ab2f86c60bc732322248eb99b64703856ff9af --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Debug/objects.mk @@ -0,0 +1,8 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +USER_OBJS := + +LIBS := -lrsa -Wl,--start-group,-lxil,-lgcc,-lc,--end-group + diff --git a/quad/xsdk_workspace/zybo_fsbl/Debug/sources.mk b/quad/xsdk_workspace/zybo_fsbl/Debug/sources.mk new file mode 100644 index 0000000000000000000000000000000000000000..a7c54c38a1e61325feea8965fd7f659ed223d79b --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Debug/sources.mk @@ -0,0 +1,20 @@ +################################################################################ +# 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 \ + diff --git a/quad/xsdk_workspace/zybo_fsbl/Debug/src/subdir.mk b/quad/xsdk_workspace/zybo_fsbl/Debug/src/subdir.mk new file mode 100644 index 0000000000000000000000000000000000000000..d3c44151fc0926a6bfab9a6c5516b0d6a7b96239 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Debug/src/subdir.mk @@ -0,0 +1,80 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +# Add inputs and outputs from these tool invocations to the build variables +C_SRCS += \ +../src/ddr_init.c \ +../src/ff.c \ +../src/fsbl_hooks.c \ +../src/image_mover.c \ +../src/main.c \ +../src/md5.c \ +../src/mmc.c \ +../src/nand.c \ +../src/nor.c \ +../src/pcap.c \ +../src/ps7_init.c \ +../src/qspi.c \ +../src/rsa.c \ +../src/sd.c + +LD_SRCS += \ +../src/lscript.ld + +S_UPPER_SRCS += \ +../src/fsbl_handoff.S + +OBJS += \ +./src/ddr_init.o \ +./src/ff.o \ +./src/fsbl_handoff.o \ +./src/fsbl_hooks.o \ +./src/image_mover.o \ +./src/main.o \ +./src/md5.o \ +./src/mmc.o \ +./src/nand.o \ +./src/nor.o \ +./src/pcap.o \ +./src/ps7_init.o \ +./src/qspi.o \ +./src/rsa.o \ +./src/sd.o + +C_DEPS += \ +./src/ddr_init.d \ +./src/ff.d \ +./src/fsbl_hooks.d \ +./src/image_mover.d \ +./src/main.d \ +./src/md5.d \ +./src/mmc.d \ +./src/nand.d \ +./src/nor.d \ +./src/pcap.d \ +./src/ps7_init.d \ +./src/qspi.d \ +./src/rsa.d \ +./src/sd.d + +S_UPPER_DEPS += \ +./src/fsbl_handoff.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 -c -fmessage-length=0 -I../../zybo_fsbl_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +src/%.o: ../src/%.S + @echo 'Building file: $<' + @echo 'Invoking: ARM gcc compiler' + arm-xilinx-eabi-gcc -Wall -O0 -g3 -c -fmessage-length=0 -I../../zybo_fsbl_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + + diff --git a/quad/xsdk_workspace/zybo_fsbl/Release/makefile b/quad/xsdk_workspace/zybo_fsbl/Release/makefile new file mode 100644 index 0000000000000000000000000000000000000000..97959e1ede4a1a3378f2241945e4d9dc184546ac --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Release/makefile @@ -0,0 +1,58 @@ +################################################################################ +# 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 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 += \ +zybo_fsbl.elf.size \ + + +# All Target +all: zybo_fsbl.elf secondary-outputs + +# Tool invocations +zybo_fsbl.elf: $(OBJS) ../src/lscript.ld $(USER_OBJS) + @echo 'Building target: $@' + @echo 'Invoking: ARM gcc linker' + arm-xilinx-eabi-gcc -L"/local/ucart/MicroCART_17-18/quad/xsdk_workspace/zybo_fsbl/src" -Wl,-T -Wl,../src/lscript.ld -L../../zybo_fsbl_bsp/ps7_cortexa9_0/lib -o "zybo_fsbl.elf" $(OBJS) $(USER_OBJS) $(LIBS) + @echo 'Finished building target: $@' + @echo ' ' + +zybo_fsbl.elf.size: zybo_fsbl.elf + @echo 'Invoking: ARM Print Size' + arm-xilinx-eabi-size zybo_fsbl.elf |tee "zybo_fsbl.elf.size" + @echo 'Finished building: $@' + @echo ' ' + +# Other Targets +clean: + -$(RM) $(OBJS)$(C_DEPS)$(EXECUTABLES)$(ELFSIZE)$(S_UPPER_DEPS) zybo_fsbl.elf + -@echo ' ' + +secondary-outputs: $(ELFSIZE) + +.PHONY: all clean dependents +.SECONDARY: + +-include ../makefile.targets diff --git a/quad/xsdk_workspace/zybo_fsbl/Release/objects.mk b/quad/xsdk_workspace/zybo_fsbl/Release/objects.mk new file mode 100644 index 0000000000000000000000000000000000000000..88ab2f86c60bc732322248eb99b64703856ff9af --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Release/objects.mk @@ -0,0 +1,8 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +USER_OBJS := + +LIBS := -lrsa -Wl,--start-group,-lxil,-lgcc,-lc,--end-group + diff --git a/quad/xsdk_workspace/zybo_fsbl/Release/sources.mk b/quad/xsdk_workspace/zybo_fsbl/Release/sources.mk new file mode 100644 index 0000000000000000000000000000000000000000..a7c54c38a1e61325feea8965fd7f659ed223d79b --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Release/sources.mk @@ -0,0 +1,20 @@ +################################################################################ +# 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 \ + diff --git a/quad/xsdk_workspace/zybo_fsbl/Release/src/subdir.mk b/quad/xsdk_workspace/zybo_fsbl/Release/src/subdir.mk new file mode 100644 index 0000000000000000000000000000000000000000..c45bb40c493a6c0fde19fd2ef6eaa2600e0e6fbb --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/Release/src/subdir.mk @@ -0,0 +1,80 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +# Add inputs and outputs from these tool invocations to the build variables +C_SRCS += \ +../src/ddr_init.c \ +../src/ff.c \ +../src/fsbl_hooks.c \ +../src/image_mover.c \ +../src/main.c \ +../src/md5.c \ +../src/mmc.c \ +../src/nand.c \ +../src/nor.c \ +../src/pcap.c \ +../src/ps7_init.c \ +../src/qspi.c \ +../src/rsa.c \ +../src/sd.c + +LD_SRCS += \ +../src/lscript.ld + +S_UPPER_SRCS += \ +../src/fsbl_handoff.S + +OBJS += \ +./src/ddr_init.o \ +./src/ff.o \ +./src/fsbl_handoff.o \ +./src/fsbl_hooks.o \ +./src/image_mover.o \ +./src/main.o \ +./src/md5.o \ +./src/mmc.o \ +./src/nand.o \ +./src/nor.o \ +./src/pcap.o \ +./src/ps7_init.o \ +./src/qspi.o \ +./src/rsa.o \ +./src/sd.o + +C_DEPS += \ +./src/ddr_init.d \ +./src/ff.d \ +./src/fsbl_hooks.d \ +./src/image_mover.d \ +./src/main.d \ +./src/md5.d \ +./src/mmc.d \ +./src/nand.d \ +./src/nor.d \ +./src/pcap.d \ +./src/ps7_init.d \ +./src/qspi.d \ +./src/rsa.d \ +./src/sd.d + +S_UPPER_DEPS += \ +./src/fsbl_handoff.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 -O2 -c -fmessage-length=0 -I../../zybo_fsbl_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + +src/%.o: ../src/%.S + @echo 'Building file: $<' + @echo 'Invoking: ARM gcc compiler' + arm-xilinx-eabi-gcc -Wall -O2 -c -fmessage-length=0 -I../../zybo_fsbl_bsp/ps7_cortexa9_0/include -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" + @echo 'Finished building: $<' + @echo ' ' + + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ddr_init.c b/quad/xsdk_workspace/zybo_fsbl/src/ddr_init.c new file mode 100644 index 0000000000000000000000000000000000000000..bf9a059a68a3d536e76e5c8f98e7e6c2219b7a0b --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/ddr_init.c @@ -0,0 +1,291 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file ddr_init.c +* +* Initialize the DDR controller. When PCW is functioning, this would be gone. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ----------------------------------------------- +* 1.00a ecm 06/19/09 First release +* 2.00a jz 05/11/11 Changed register to #defines, updated to peep11 +* 3.00a mb 30/05/12 included fsbl.h +* </pre> +* +******************************************************************************/ + +/***************************** Include Files *********************************/ + +#include "xil_io.h" +#include "fsbl.h" + +/************************** Constant Definitions *****************************/ +#define DDR_CONFIG_BASE (XPS_DDR_CTRL_BASEADDR + 0x000) + +#define DDR_MSTR_CTRL_REG (XPS_DDR_CTRL_BASEADDR + 0x000) + +#define DDR_TWORANKPHY_REG (XPS_DDR_CTRL_BASEADDR + 0x004) + +#define DDR_HPR_PARAMS_REG (XPS_DDR_CTRL_BASEADDR + 0x008) +#define DDR_LPR_PARAMS_REG (XPS_DDR_CTRL_BASEADDR + 0x00C) +#define DDR_W_PARAMS_REG (XPS_DDR_CTRL_BASEADDR + 0x010) +#define DDR_DRAM_PARAMS_1_REG (XPS_DDR_CTRL_BASEADDR + 0x014) +#define DDR_DRAM_PARAMS_2_REG (XPS_DDR_CTRL_BASEADDR + 0x018) +#define DDR_DRAM_PARAMS_3_REG (XPS_DDR_CTRL_BASEADDR + 0x01C) +#define DDR_DRAM_PARAMS_4_REG (XPS_DDR_CTRL_BASEADDR + 0x020) +#define DDR_DRAM_PARAMS_5_REG (XPS_DDR_CTRL_BASEADDR + 0x024) +#define DDR_DRAM_INIT_PARAMS_REG (XPS_DDR_CTRL_BASEADDR + 0x028) + +#define DDR_DRAM_MODE_1_REG (XPS_DDR_CTRL_BASEADDR + 0x02C) +#define DDR_DRAM_MODE_2_REG (XPS_DDR_CTRL_BASEADDR + 0x030) +#define DDR_DRAM_BURST8_REG (XPS_DDR_CTRL_BASEADDR + 0x034) + +#define DDR_DEBUG_REG (XPS_DDR_CTRL_BASEADDR + 0x038) + +#define DDR_ADDR_MAP_1_REG (XPS_DDR_CTRL_BASEADDR + 0x03C) +#define DDR_ADDR_MAP_2_REG (XPS_DDR_CTRL_BASEADDR + 0x040) +#define DDR_ADDR_MAP_3_REG (XPS_DDR_CTRL_BASEADDR + 0x044) + +#define DDR_ODT_RD_WR_REG (XPS_DDR_CTRL_BASEADDR + 0x048) +#define DDR_PHY_RDC_FIFO_CTRL_REG (XPS_DDR_CTRL_BASEADDR + 0x04C) +#define DDR_REG_PHY_RDC_FIFO_CTRL (XPS_DDR_CTRL_BASEADDR + 0x050) +#define DDR_STATUS_REG (XPS_DDR_CTRL_BASEADDR + 0x054) + +#define DDR_DLL_CALIB_REG (XPS_DDR_CTRL_BASEADDR + 0x058) +#define DDR_ODT_REG (XPS_DDR_CTRL_BASEADDR + 0x05C) +#define DDR_MISC_1_REG (XPS_DDR_CTRL_BASEADDR + 0x060) +#define DDR_MISC_2_REG (XPS_DDR_CTRL_BASEADDR + 0x064) + +#define DDR_WR_DLL_FORCE (XPS_DDR_CTRL_BASEADDR + 0x068) +#define DDR_RD_DLL_FORCE0_REG (XPS_DDR_CTRL_BASEADDR + 0x06C) +#define DDR_RD_DLL_FORCE1_REG (XPS_DDR_CTRL_BASEADDR + 0x070) + +#define DDR_WR_RATIO_REG (XPS_DDR_CTRL_BASEADDR + 0x074) +#define DDR_RD_RATIO_REG (XPS_DDR_CTRL_BASEADDR + 0x078) + +#define DDR_MSTR_DLL_STATUS1_REG (XPS_DDR_CTRL_BASEADDR + 0x07C) +#define DDR_RD_SLAVE_STATUS0_REG (XPS_DDR_CTRL_BASEADDR + 0x080) +#define DDR_RD_SLAVE_STATUS1_REG (XPS_DDR_CTRL_BASEADDR + 0x084) + +#define DDR_OF_STATUS0_REG (XPS_DDR_CTRL_BASEADDR + 0x088) +#define DDR_OF_STATUS1_REG (XPS_DDR_CTRL_BASEADDR + 0x08C) +#define DDR_OF_STATUS2_REG (XPS_DDR_CTRL_BASEADDR + 0x090) +#define DDR_OF_STATUS3_REG (XPS_DDR_CTRL_BASEADDR + 0x094) + +#define DDR_MSTR_DLL_STATUS2_REG (XPS_DDR_CTRL_BASEADDR + 0x098) + +#define DDR_Wr_DLL_FORCE1_REG (XPS_DDR_CTRL_BASEADDR + 0x09C) +#define DDR_REFRESH_TIMER01_REG (XPS_DDR_CTRL_BASEADDR + 0x0A0) +#define DDR_T_ZQ_REG (XPS_DDR_CTRL_BASEADDR + 0x0A4) +#define DDR_T_ZQ_SHORT_INTERVAL_REG (XPS_DDR_CTRL_BASEADDR + 0x0A8) + +#define DDR_STATUS_DATA_SL_DLL_01_REG (XPS_DDR_CTRL_BASEADDR + 0x0AC) +#define DDR_STATUS_DATA_SL_DLL_23_REG (XPS_DDR_CTRL_BASEADDR + 0x0B0) +#define DDR_STATUS_DQS_SL_DLL_01_REG (XPS_DDR_CTRL_BASEADDR + 0x0B4) +#define DDR_STATUS_DQS_SL_DLL_23_REG (XPS_DDR_CTRL_BASEADDR + 0x0B8) + +#define DDR_WR_DATA_SLV0_REG (XPS_DDR_CTRL_BASEADDR + 0x17c) +#define DDR_WR_DATA_SLV1_REG (XPS_DDR_CTRL_BASEADDR + 0x180) +#define DDR_WR_DATA_SLV2_REG (XPS_DDR_CTRL_BASEADDR + 0x184) +#define DDR_WR_DATA_SLV3_REG (XPS_DDR_CTRL_BASEADDR + 0x188) + +#define DDR_ID_REG (XPS_DDR_CTRL_BASEADDR + 0x200) +#define DDR_DDR_CFG_REG (XPS_DDR_CTRL_BASEADDR + 0x204) + +#define DDR_PRIO_WR_PORT00_REG (XPS_DDR_CTRL_BASEADDR + 0x208) +#define DDR_PRIO_WR_PORT01_REG (XPS_DDR_CTRL_BASEADDR + 0x20C) +#define DDR_PRIO_WR_PORT02_REG (XPS_DDR_CTRL_BASEADDR + 0x210) +#define DDR_PRIO_WR_PORT03_REG (XPS_DDR_CTRL_BASEADDR + 0x214) +#define DDR_PRIO_RD_PORT00_REG (XPS_DDR_CTRL_BASEADDR + 0x218) +#define DDR_PRIO_RD_PORT01_REG (XPS_DDR_CTRL_BASEADDR + 0x21C) +#define DDR_PRIO_RD_PORT02_REG (XPS_DDR_CTRL_BASEADDR + 0x220) +#define DDR_PRIO_RD_PORT03_REG (XPS_DDR_CTRL_BASEADDR + 0x224) + +#define DDR_PERF_MON_1_PORT0_REG (XPS_DDR_CTRL_BASEADDR + 0x228) +#define DDR_PERF_MON_1_PORT1_REG (XPS_DDR_CTRL_BASEADDR + 0x22C) +#define DDR_PERF_MON_1_PORT2_REG (XPS_DDR_CTRL_BASEADDR + 0x230) +#define DDR_PERF_MON_1_PORT3_REG (XPS_DDR_CTRL_BASEADDR + 0x234) +#define DDR_PERF_MON_2_PORT0_REG (XPS_DDR_CTRL_BASEADDR + 0x238) +#define DDR_PERF_MON_2_PORT1_REG (XPS_DDR_CTRL_BASEADDR + 0x23C) +#define DDR_PERF_MON_2_PORT2_REG (XPS_DDR_CTRL_BASEADDR + 0x240) +#define DDR_PERF_MON_2_PORT3_REG (XPS_DDR_CTRL_BASEADDR + 0x244) +#define DDR_PERF_MON_3_PORT0_REG (XPS_DDR_CTRL_BASEADDR + 0x248) +#define DDR_PERF_MON_3_PORT1_REG (XPS_DDR_CTRL_BASEADDR + 0x24C) +#define DDR_PERF_MON_3_PORT2_REG (XPS_DDR_CTRL_BASEADDR + 0x250) +#define DDR_PERF_MON_3_PORT3_REG (XPS_DDR_CTRL_BASEADDR + 0x254) +#define DDR_TRUSTED_MEM_CFG_REG (XPS_DDR_CTRL_BASEADDR + 0x258) + +#define DDR_EXCLACC_CFG_PORT0_REG (XPS_DDR_CTRL_BASEADDR + 0x25C) +#define DDR_EXCLACC_CFG_PORT1_REG (XPS_DDR_CTRL_BASEADDR + 0x260) +#define DDR_EXCLACC_CFG_PORT2_REG (XPS_DDR_CTRL_BASEADDR + 0x264) +#define DDR_EXCLACC_CFG_PORT3_REG (XPS_DDR_CTRL_BASEADDR + 0x268) + +/* Trust zone configuration register */ +#define SLCR_LOCK_REG (XPS_SYS_CTRL_BASEADDR + 0x4) +#define SLCR_UNLOCK_REG (XPS_SYS_CTRL_BASEADDR + 0x8) +#define TZ_DDR_RAM_REG (XPS_SYS_CTRL_BASEADDR + 0x430) + + +/* Mask defines */ +#define DDR_OUT_RESET_MASK 0x1 + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ +#define DDRIn32 Xil_In32 +#define DDROut32 Xil_Out32 +/************************** Variable Definitions *****************************/ + +/************************** Function Prototypes ******************************/ + +void init_ddr(void); + +#define DDRIn32 Xil_In32 +#define DDROut32 Xil_Out32 + +static int verify = 0; + +static void NewDDROut32(u32 Address, u32 Value) +{ + u32 Data; + + if (verify) { + Data = DDRIn32(Address); + if (Data != Value) fsbl_printf(DEBUG_INFO,"Verify failed, Address = %08X, \ + Data = %08X, Expected = %08X\n\r", Address, Data, Value); + } else + DDROut32(Address, Value); +} + +#undef DDROut32 +#define DDROut32 NewDDROut32 + +void init_ddr(void) +{ + u32 RegValue; + + RegValue = DDRIn32(DDR_MSTR_CTRL_REG); + + /* If DDR is being taking out of reset, then it has been configured + */ + if (RegValue & DDR_OUT_RESET_MASK) + verify = 1; + + /* Configure DDR */ + DDROut32(DDR_MSTR_CTRL_REG, 0x00000200); + + /* direct rip of the DDR init tcl for the PEEP startup */ + DDROut32(DDR_TWORANKPHY_REG, 0x000C1061); /* # 0 */ + + DDROut32(DDR_LPR_PARAMS_REG, 0x03001001); //;#3 + DDROut32(DDR_W_PARAMS_REG, 0x00014001); //;#4 + + DDROut32(DDR_DRAM_PARAMS_1_REG, 0x0004e020); //; #5 + +#ifdef PEEP_CODE + DDROut32(DDR_DRAM_PARAMS_2_REG, 0x36264ccf); //; #6 +#else + DDROut32(DDR_DRAM_PARAMS_2_REG, 0x349B48CD); //; #6 +#endif + DDROut32(DDR_DRAM_PARAMS_3_REG, 0x820158a4); //; #7 + + DDROut32(DDR_DRAM_PARAMS_4_REG, 0x250882c4); //; #8 + + DDROut32(DDR_DRAM_INIT_PARAMS_REG, 0x00809004); //; #10 + + DDROut32(DDR_DRAM_MODE_1_REG, 0x0); //; #11 + + DDROut32(DDR_DRAM_MODE_2_REG, 0x00040952); //; #12 + + DDROut32(DDR_DRAM_BURST8_REG, 0x00020022); //; #13 + +#ifdef PEEP_CODE + DDROut32(DDR_ADDR_MAP_1_REG, 0xF88); //; #15 +#endif + +#ifdef PALLADIUM + DDROut32(DDR_ADDR_MAP_1_REG, 0x777); //; #15 +#endif + + DDROut32(DDR_ADDR_MAP_2_REG, 0xFF000000); //; #16 + + DDROut32(DDR_ADDR_MAP_3_REG, 0x0FF66666); //; #17 + + DDROut32(DDR_REG_PHY_RDC_FIFO_CTRL, 0x256); //; #20 + + DDROut32(DDR_ODT_REG, 0x2223); //; #23 + + DDROut32(DDR_MISC_2_REG, 0x00020FE0); //; #25 + + DDROut32(DDR_T_ZQ_REG, 0x10200800); //; #41 + + DDROut32(DDR_STATUS_DQS_SL_DLL_23_REG, 0x200065); //; #46 + + DDROut32(DDR_WR_DATA_SLV0_REG, 0x50); //; #95 + + DDROut32(DDR_WR_DATA_SLV1_REG, 0x50); //; #96 + + DDROut32(DDR_WR_DATA_SLV2_REG, 0x50); //; #97 + + DDROut32(DDR_WR_DATA_SLV3_REG, 0x50); //; #98 + + DDROut32(DDR_ID_REG, 0x0); //; #128 + + /* Enable ddr controller by taking the controller out of reset */ + DDROut32(DDR_MSTR_CTRL_REG, + DDRIn32(DDR_MSTR_CTRL_REG) | DDR_OUT_RESET_MASK); + +#ifdef PALLADIUM + + /* Workaround for early palladium, to be removed for 4.61 */ + DDROut32(SLCR_UNLOCK_REG, 0xDF0D); + + DDROut32(TZ_DDR_RAM_REG, 0xffffffff); + + DDROut32(SLCR_LOCK_REG, 0x767B); + +#endif /* PALLADIUM*/ +} diff --git a/quad/xsdk_workspace/zybo_fsbl/src/diskio.h b/quad/xsdk_workspace/zybo_fsbl/src/diskio.h new file mode 100644 index 0000000000000000000000000000000000000000..5244efd77904e1023716a9990361208340a461e2 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/diskio.h @@ -0,0 +1,51 @@ +/*----------------------------------------------------------------------- +/ Low level disk interface modlue include file (C)ChaN, 2009 +/-----------------------------------------------------------------------*/ + +#ifndef _DISKIO +#define _DISKIO + +#include "integer.h" + + +/* Status of Disk Functions */ +typedef BYTE DSTATUS; + +/* Results of Disk Functions */ +typedef enum { + RES_OK = 0, /* 0: Successful */ + RES_ERROR, /* 1: R/W Error */ + RES_WRPRT, /* 2: Write Protected */ + RES_NOTRDY, /* 3: Not Ready */ + RES_PARERR /* 4: Invalid Parameter */ +} DRESULT; + + +/*---------------------------------------*/ +/* Prototypes for disk control functions */ + +int assign_drives (int, int); +DSTATUS disk_initialize (BYTE); +DSTATUS disk_status (BYTE); +DRESULT disk_read (BYTE, BYTE*, DWORD, BYTE); +DRESULT disk_write (BYTE, const BYTE*, DWORD, BYTE); +DRESULT disk_ioctl (BYTE, BYTE, void*); + + + +/* Disk Status Bits (DSTATUS) */ + +#define STA_NOINIT 0x01 /* Drive not initialized */ +#define STA_NODISK 0x02 /* No medium in the drive */ +#define STA_PROTECT 0x04 /* Write protected */ + + +/* Command code for disk_ioctrl fucntion */ + +/* Generic command (mandatory for FatFs) */ +#define CTRL_SYNC 0 /* Flush disk cache (for write functions) */ +#define GET_SECTOR_COUNT 1 /* Get media size (for only f_mkfs()) */ +#define GET_SECTOR_SIZE 2 /* Get sector size (for multiple sector size (_MAX_SS >= 1024)) */ +#define GET_BLOCK_SIZE 3 /* Get erase block size (for only f_mkfs()) */ + +#endif diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ff.c b/quad/xsdk_workspace/zybo_fsbl/src/ff.c new file mode 100644 index 0000000000000000000000000000000000000000..35bfa7e50afb44e44833ae218af15355a7210ea7 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/ff.c @@ -0,0 +1,3756 @@ +/*----------------------------------------------------------------------------/ +/ FatFs - FAT file system module R0.08a (C)ChaN, 2010 +/-----------------------------------------------------------------------------/ +/ FatFs module is a generic FAT file system module for small embedded systems. +/ This is a free software that opened for education, research and commercial +/ developments under license policy of following terms. +/ +/ Copyright (C) 2010, ChaN, all right reserved. +/ +/ * The FatFs module is a free software and there is NO WARRANTY. +/ * No restriction on use. You can use, modify and redistribute it for +/ personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY. +/ * Redistributions of source code must retain the above copyright notice. +/ +/-----------------------------------------------------------------------------/ +/ Feb 26,'06 R0.00 Prototype. +/ +/ Apr 29,'06 R0.01 First stable version. +/ +/ Jun 01,'06 R0.02 Added FAT12 support. +/ Removed unbuffered mode. +/ Fixed a problem on small (<32M) partition. +/ Jun 10,'06 R0.02a Added a configuration option (_FS_MINIMUM). +/ +/ Sep 22,'06 R0.03 Added f_rename(). +/ Changed option _FS_MINIMUM to _FS_MINIMIZE. +/ Dec 11,'06 R0.03a Improved cluster scan algorithm to write files fast. +/ Fixed f_mkdir() creates incorrect directory on FAT32. +/ +/ Feb 04,'07 R0.04 Supported multiple drive system. +/ Changed some interfaces for multiple drive system. +/ Changed f_mountdrv() to f_mount(). +/ Added f_mkfs(). +/ Apr 01,'07 R0.04a Supported multiple partitions on a physical drive. +/ Added a capability of extending file size to f_lseek(). +/ Added minimization level 3. +/ Fixed an endian sensitive code in f_mkfs(). +/ May 05,'07 R0.04b Added a configuration option _USE_NTFLAG. +/ Added FSInfo support. +/ Fixed DBCS name can result FR_INVALID_NAME. +/ Fixed short seek (<= csize) collapses the file object. +/ +/ Aug 25,'07 R0.05 Changed arguments of f_read(), f_write() and f_mkfs(). +/ Fixed f_mkfs() on FAT32 creates incorrect FSInfo. +/ Fixed f_mkdir() on FAT32 creates incorrect directory. +/ Feb 03,'08 R0.05a Added f_truncate() and f_utime(). +/ Fixed off by one error at FAT sub-type determination. +/ Fixed btr in f_read() can be mistruncated. +/ Fixed cached sector is not flushed when create and close without write. +/ +/ Apr 01,'08 R0.06 Added fputc(), fputs(), fprintf() and fgets(). +/ Improved performance of f_lseek() on moving to the same or following cluster. +/ +/ Apr 01,'09 R0.07 Merged Tiny-FatFs as a buffer configuration option. (_FS_TINY) +/ Added long file name support. +/ Added multiple code page support. +/ Added re-entrancy for multitask operation. +/ Added auto cluster size selection to f_mkfs(). +/ Added rewind option to f_readdir(). +/ Changed result code of critical errors. +/ Renamed string functions to avoid name collision. +/ Apr 14,'09 R0.07a Separated out OS dependent code on reentrant cfg. +/ Added multiple sector size support. +/ Jun 21,'09 R0.07c Fixed f_unlink() can return FR_OK on error. +/ Fixed wrong cache control in f_lseek(). +/ Added relative path feature. +/ Added f_chdir() and f_chdrive(). +/ Added proper case conversion to extended char. +/ Nov 03,'09 R0.07e Separated out configuration options from ff.h to ffconf.h. +/ Fixed f_unlink() fails to remove a sub-dir on _FS_RPATH. +/ Fixed name matching error on the 13 char boundary. +/ Added a configuration option, _LFN_UNICODE. +/ Changed f_readdir() to return the SFN with always upper case on non-LFN cfg. +/ +/ May 15,'10 R0.08 Added a memory configuration option. (_USE_LFN = 3) +/ Added file lock feature. (_FS_SHARE) +/ Added fast seek feature. (_USE_FASTSEEK) +/ Changed some types on the API, XCHAR->TCHAR. +/ Changed fname member in the FILINFO structure on Unicode cfg. +/ String functions support UTF-8 encoding files on Unicode cfg. +/ Aug 16,'10 R0.08a Added f_getcwd(). (_FS_RPATH = 2) +/ Added sector erase feature. (_USE_ERASE) +/ Moved file lock semaphore table from fs object to the bss. +/ Fixed a wrong directory entry is created on non-LFN cfg when the given name contains ';'. +/ Fixed f_mkfs() creates wrong FAT32 volume. +/---------------------------------------------------------------------------*/ +#include "xparameters.h" +#ifdef XPAR_PS7_SD_0_S_AXI_BASEADDR +#include "ff.h" /* FatFs configurations and declarations */ +#include "diskio.h" /* Declarations of low level disk I/O functions */ + +/*-------------------------------------------------------------------------- + + Module Private Definitions + +---------------------------------------------------------------------------*/ + +#if _FATFS != 8255 +#error Wrong include file (ff.h). +#endif + + +/* Definitions on sector size */ +#if _MAX_SS != 512 && _MAX_SS != 1024 && _MAX_SS != 2048 && _MAX_SS != 4096 +#error Wrong sector size. +#endif +#if _MAX_SS != 512 +#define SS(fs) ((fs)->ssize) /* Multiple sector size */ +#else +#define SS(fs) 512U /* Fixed sector size */ +#endif + + +/* Reentrancy related */ +#if _FS_REENTRANT +#if _USE_LFN == 1 +#error Static LFN work area must not be used in re-entrant configuration. +#endif +#define ENTER_FF(fs) { if (!lock_fs(fs)) return FR_TIMEOUT; } +#define LEAVE_FF(fs, res) { unlock_fs(fs, res); return res; } +#else +#define ENTER_FF(fs) +#define LEAVE_FF(fs, res) return res +#endif + +#define ABORT(fs, res) { fp->flag |= FA__ERROR; LEAVE_FF(fs, res); } + + +/* File shareing feature */ +#if _FS_SHARE +#if _FS_READONLY +#error _FS_SHARE must be 0 on read-only cfg. +#endif +typedef struct { + FATFS *fs; /* File ID 1, volume (NULL:blank entry) */ + DWORD clu; /* File ID 2, directory */ + WORD idx; /* File ID 3, directory index */ + WORD ctr; /* File open counter, 0:none, 0x01..0xFF:read open count, 0x100:write mode */ +} FILESEM; +#endif + + +/* Misc definitions */ +#define LD_CLUST(dir) (((DWORD)LD_WORD(dir+DIR_FstClusHI)<<16) | LD_WORD(dir+DIR_FstClusLO)) +#define ST_CLUST(dir,cl) {ST_WORD(dir+DIR_FstClusLO, cl); ST_WORD(dir+DIR_FstClusHI, (DWORD)cl>>16);} + + +/* Character code support macros */ +#define IsUpper(c) (((c)>='A')&&((c)<='Z')) +#define IsLower(c) (((c)>='a')&&((c)<='z')) +#define IsDigit(c) (((c)>='0')&&((c)<='9')) + +#if _DF1S /* Code page is DBCS */ + +#ifdef _DF2S /* Two 1st byte areas */ +#define IsDBCS1(c) (((BYTE)(c) >= _DF1S && (BYTE)(c) <= _DF1E) || ((BYTE)(c) >= _DF2S && (BYTE)(c) <= _DF2E)) +#else /* One 1st byte area */ +#define IsDBCS1(c) ((BYTE)(c) >= _DF1S && (BYTE)(c) <= _DF1E) +#endif + +#ifdef _DS3S /* Three 2nd byte areas */ +#define IsDBCS2(c) (((BYTE)(c) >= _DS1S && (BYTE)(c) <= _DS1E) || ((BYTE)(c) >= _DS2S && (BYTE)(c) <= _DS2E) || ((BYTE)(c) >= _DS3S && (BYTE)(c) <= _DS3E)) +#else /* Two 2nd byte areas */ +#define IsDBCS2(c) (((BYTE)(c) >= _DS1S && (BYTE)(c) <= _DS1E) || ((BYTE)(c) >= _DS2S && (BYTE)(c) <= _DS2E)) +#endif + +#else /* Code page is SBCS */ + +#define IsDBCS1(c) 0 +#define IsDBCS2(c) 0 + +#endif /* _DF1S */ + + +/* Name status flags */ +#define NS 11 /* Offset of name status byte */ +#define NS_LOSS 0x01 /* Out of 8.3 format */ +#define NS_LFN 0x02 /* Force to create LFN entry */ +#define NS_LAST 0x04 /* Last segment */ +#define NS_BODY 0x08 /* Lower case flag (body) */ +#define NS_EXT 0x10 /* Lower case flag (ext) */ +#define NS_DOT 0x20 /* Dot entry */ + + +/* FAT sub-type boundaries */ +/* Note that the FAT spec by Microsoft says 4085 but Windows works with 4087! */ +#define MIN_FAT16 4086 /* Minimum number of clusters for FAT16 */ +#define MIN_FAT32 65526 /* Minimum number of clusters for FAT32 */ + + +/* FatFs refers the members in the FAT structures as byte array instead of +/ structure member because there are incompatibility of the packing option +/ between compilers. */ + +#define BS_jmpBoot 0 +#define BS_OEMName 3 +#define BPB_BytsPerSec 11 +#define BPB_SecPerClus 13 +#define BPB_RsvdSecCnt 14 +#define BPB_NumFATs 16 +#define BPB_RootEntCnt 17 +#define BPB_TotSec16 19 +#define BPB_Media 21 +#define BPB_FATSz16 22 +#define BPB_SecPerTrk 24 +#define BPB_NumHeads 26 +#define BPB_HiddSec 28 +#define BPB_TotSec32 32 +#define BS_DrvNum 36 +#define BS_BootSig 38 +#define BS_VolID 39 +#define BS_VolLab 43 +#define BS_FilSysType 54 +#define BPB_FATSz32 36 +#define BPB_ExtFlags 40 +#define BPB_FSVer 42 +#define BPB_RootClus 44 +#define BPB_FSInfo 48 +#define BPB_BkBootSec 50 +#define BS_DrvNum32 64 +#define BS_BootSig32 66 +#define BS_VolID32 67 +#define BS_VolLab32 71 +#define BS_FilSysType32 82 +#define FSI_LeadSig 0 +#define FSI_StrucSig 484 +#define FSI_Free_Count 488 +#define FSI_Nxt_Free 492 +#define MBR_Table 446 +#define BS_55AA 510 + +#define DIR_Name 0 +#define DIR_Attr 11 +#define DIR_NTres 12 +#define DIR_CrtTime 14 +#define DIR_CrtDate 16 +#define DIR_FstClusHI 20 +#define DIR_WrtTime 22 +#define DIR_WrtDate 24 +#define DIR_FstClusLO 26 +#define DIR_FileSize 28 +#define LDIR_Ord 0 +#define LDIR_Attr 11 +#define LDIR_Type 12 +#define LDIR_Chksum 13 +#define LDIR_FstClusLO 26 + + + +/*------------------------------------------------------------*/ +/* Work area */ + +#if _VOLUMES +static +FATFS *FatFs[_VOLUMES]; /* Pointer to the file system objects (logical drives) */ +#else +#error Number of drives must not be 0. +#endif + +static +WORD Fsid; /* File system mount ID */ + +#if _FS_RPATH +static +BYTE CurrVol; /* Current drive */ +#endif + +#if _FS_SHARE +static +FILESEM Files[_FS_SHARE]; /* File lock semaphores */ +#endif + +#if _USE_LFN == 0 /* No LFN */ +#define DEF_NAMEBUF BYTE sfn[12] +#define INIT_BUF(dobj) (dobj).fn = sfn +#define FREE_BUF() + +#elif _USE_LFN == 1 /* LFN with static LFN working buffer */ +static WCHAR LfnBuf[_MAX_LFN+1]; +#define DEF_NAMEBUF BYTE sfn[12] +#define INIT_BUF(dobj) { (dobj).fn = sfn; (dobj).lfn = LfnBuf; } +#define FREE_BUF() + +#elif _USE_LFN == 2 /* LFN with dynamic LFN working buffer on the stack */ +#define DEF_NAMEBUF BYTE sfn[12]; WCHAR lbuf[_MAX_LFN+1] +#define INIT_BUF(dobj) { (dobj).fn = sfn; (dobj).lfn = lbuf; } +#define FREE_BUF() + +#elif _USE_LFN == 3 /* LFN with dynamic LFN working buffer on the heap */ +#define DEF_NAMEBUF BYTE sfn[12]; WCHAR *lfn +#define INIT_BUF(dobj) { lfn = ff_memalloc((_MAX_LFN + 1) * 2); \ + if (!lfn) LEAVE_FF((dobj).fs, FR_NOT_ENOUGH_CORE); \ + (dobj).lfn = lfn; (dobj).fn = sfn; } +#define FREE_BUF() ff_memfree(lfn) + +#else +#error Wrong LFN configuration. +#endif + + + + +/*-------------------------------------------------------------------------- + + Module Private Functions + +---------------------------------------------------------------------------*/ + + +/*-----------------------------------------------------------------------*/ +/* String functions */ +/*-----------------------------------------------------------------------*/ + +/* Copy memory to memory */ +static +void mem_cpy (void* dst, const void* src, UINT cnt) { + BYTE *d = (BYTE*)dst; + const BYTE *s = (const BYTE*)src; + +#if _WORD_ACCESS == 1 + while (cnt >= sizeof(int)) { + *(int*)d = *(int*)s; + d += sizeof(int); s += sizeof(int); + cnt -= sizeof(int); + } +#endif + while (cnt--) + *d++ = *s++; +} + +/* Fill memory */ +static +void mem_set (void* dst, int val, UINT cnt) { + BYTE *d = (BYTE*)dst; + + while (cnt--) + *d++ = (BYTE)val; +} + +/* Compare memory to memory */ +static +int mem_cmp (const void* dst, const void* src, UINT cnt) { + const BYTE *d = (const BYTE *)dst, *s = (const BYTE *)src; + int r = 0; + + while (cnt-- && (r = *d++ - *s++) == 0) ; + return r; +} + +/* Check if chr is contained in the string */ +static +int chk_chr (const char* str, int chr) { + while (*str && *str != chr) str++; + return *str; +} + + + +/*-----------------------------------------------------------------------*/ +/* Request/Release grant to access the volume */ +/*-----------------------------------------------------------------------*/ +#if _FS_REENTRANT + +static +int lock_fs ( + FATFS *fs /* File system object */ +) +{ + return ff_req_grant(fs->sobj); +} + + +static +void unlock_fs ( + FATFS *fs, /* File system object */ + FRESULT res /* Result code to be returned */ +) +{ + if (res != FR_NOT_ENABLED && + res != FR_INVALID_DRIVE && + res != FR_INVALID_OBJECT && + res != FR_TIMEOUT) { + ff_rel_grant(fs->sobj); + } +} +#endif + + + +/*-----------------------------------------------------------------------*/ +/* File shareing control functions */ +/*-----------------------------------------------------------------------*/ +#if _FS_SHARE + +static +FRESULT chk_lock ( /* Check if the file can be accessed */ + DIR* dj, /* Directory object pointing the file to be checked */ + int acc /* Desired access (0:Read, 1:Write, 2:Delete/Rename) */ +) +{ + UINT i, be; + + /* Search file semaphore table */ + for (i = be = 0; i < _FS_SHARE; i++) { + if (Files[i].fs) { /* Existing entry */ + if (Files[i].fs == dj->fs && /* Check if the file matched with an open file */ + Files[i].clu == dj->sclust && + Files[i].idx == dj->index) break; + } else { /* Blank entry */ + be++; + } + } + if (i == _FS_SHARE) /* The file is not opened */ + return (be || acc == 2) ? FR_OK : FR_TOO_MANY_OPEN_FILES; /* Is there a blank entry for new file? */ + + /* The file has been opened. Reject any open against writing file and all write mode open */ + return (acc || Files[i].ctr == 0x100) ? FR_LOCKED : FR_OK; +} + + +static +int enq_lock ( /* Check if an entry is available for a new file */ + FATFS* fs /* File system object */ +) +{ + UINT i; + + for (i = 0; i < _FS_SHARE && Files[i].fs; i++) ; + return (i == _FS_SHARE) ? 0 : 1; +} + + +static +UINT inc_lock ( /* Increment file open counter and returns its index (0:int error) */ + DIR* dj, /* Directory object pointing the file to register or increment */ + int acc /* Desired access mode (0:Read, !0:Write) */ +) +{ + UINT i; + + + for (i = 0; i < _FS_SHARE; i++) { /* Find the file */ + if (Files[i].fs == dj->fs && + Files[i].clu == dj->sclust && + Files[i].idx == dj->index) break; + } + + if (i == _FS_SHARE) { /* Not opened. Register it as new. */ + for (i = 0; i < _FS_SHARE && Files[i].fs; i++) ; + if (i == _FS_SHARE) return 0; /* No space to register (int err) */ + Files[i].fs = dj->fs; + Files[i].clu = dj->sclust; + Files[i].idx = dj->index; + Files[i].ctr = 0; + } + + if (acc && Files[i].ctr) return 0; /* Access violation (int err) */ + + Files[i].ctr = acc ? 0x100 : Files[i].ctr + 1; /* Set semaphore value */ + + return i + 1; +} + + +static +FRESULT dec_lock ( /* Decrement file open counter */ + UINT i /* Semaphore index */ +) +{ + WORD n; + FRESULT res; + + + if (--i < _FS_SHARE) { + n = Files[i].ctr; + if (n == 0x100) n = 0; + if (n) n--; + Files[i].ctr = n; + if (!n) Files[i].fs = 0; + res = FR_OK; + } else { + res = FR_INT_ERR; + } + return res; +} + + +static +void clear_lock ( /* Clear lock entries of the volume */ + FATFS *fs +) +{ + UINT i; + + for (i = 0; i < _FS_SHARE; i++) { + if (Files[i].fs == fs) Files[i].fs = 0; + } +} +#endif + + + +/*-----------------------------------------------------------------------*/ +/* Change window offset */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT move_window ( + FATFS *fs, /* File system object */ + DWORD sector /* Sector number to make appearance in the fs->win[] */ +) /* Move to zero only writes back dirty window */ +{ + DWORD wsect; + + wsect = fs->winsect; + if (wsect != sector) { /* Changed current window */ +#if !_FS_READONLY + if (fs->wflag) { /* Write back dirty window if needed */ + if (disk_write(fs->drv, fs->win, wsect, 1) != RES_OK) + return FR_DISK_ERR; + fs->wflag = 0; + if (wsect < (fs->fatbase + fs->fsize)) { /* In FAT area */ + BYTE nf; + for (nf = fs->n_fats; nf > 1; nf--) { /* Reflect the change to all FAT copies */ + wsect += fs->fsize; + disk_write(fs->drv, fs->win, wsect, 1); + } + } + } +#endif + if (sector) { + if (disk_read(fs->drv, fs->win, sector, 1) != RES_OK) + return FR_DISK_ERR; + fs->winsect = sector; + } + } + + return FR_OK; +} + + + + +/*-----------------------------------------------------------------------*/ +/* Clean-up cached data */ +/*-----------------------------------------------------------------------*/ +#if !_FS_READONLY +static +FRESULT sync ( /* FR_OK: successful, FR_DISK_ERR: failed */ + FATFS *fs /* File system object */ +) +{ + FRESULT res; + + + res = move_window(fs, 0); + if (res == FR_OK) { + /* Update FSInfo sector if needed */ + if (fs->fs_type == FS_FAT32 && fs->fsi_flag) { + fs->winsect = 0; + mem_set(fs->win, 0, 512); + ST_WORD(fs->win+BS_55AA, 0xAA55); + ST_DWORD(fs->win+FSI_LeadSig, 0x41615252); + ST_DWORD(fs->win+FSI_StrucSig, 0x61417272); + ST_DWORD(fs->win+FSI_Free_Count, fs->free_clust); + ST_DWORD(fs->win+FSI_Nxt_Free, fs->last_clust); + disk_write(fs->drv, fs->win, fs->fsi_sector, 1); + fs->fsi_flag = 0; + } + /* Make sure that no pending write process in the physical drive */ + if (disk_ioctl(fs->drv, CTRL_SYNC, (void*)0) != RES_OK) + res = FR_DISK_ERR; + } + + return res; +} +#endif + + + + +/*-----------------------------------------------------------------------*/ +/* Get sector# from cluster# */ +/*-----------------------------------------------------------------------*/ + + +DWORD clust2sect ( /* !=0: Sector number, 0: Failed - invalid cluster# */ + FATFS *fs, /* File system object */ + DWORD clst /* Cluster# to be converted */ +) +{ + clst -= 2; + if (clst >= (fs->n_fatent - 2)) return 0; /* Invalid cluster# */ + return clst * fs->csize + fs->database; +} + + + + +/*-----------------------------------------------------------------------*/ +/* FAT access - Read value of a FAT entry */ +/*-----------------------------------------------------------------------*/ + + +DWORD get_fat ( /* 0xFFFFFFFF:Disk error, 1:Internal error, Else:Cluster status */ + FATFS *fs, /* File system object */ + DWORD clst /* Cluster# to get the link information */ +) +{ + UINT wc, bc; + BYTE *p; + + + if (clst < 2 || clst >= fs->n_fatent) /* Chack range */ + return 1; + + switch (fs->fs_type) { + case FS_FAT12 : + bc = (UINT)clst; bc += bc / 2; + if (move_window(fs, fs->fatbase + (bc / SS(fs)))) break; + wc = fs->win[bc % SS(fs)]; bc++; + if (move_window(fs, fs->fatbase + (bc / SS(fs)))) break; + wc |= fs->win[bc % SS(fs)] << 8; + return (clst & 1) ? (wc >> 4) : (wc & 0xFFF); + + case FS_FAT16 : + if (move_window(fs, fs->fatbase + (clst / (SS(fs) / 2)))) break; + p = &fs->win[clst * 2 % SS(fs)]; + return LD_WORD(p); + + case FS_FAT32 : + if (move_window(fs, fs->fatbase + (clst / (SS(fs) / 4)))) break; + p = &fs->win[clst * 4 % SS(fs)]; + return LD_DWORD(p) & 0x0FFFFFFF; + } + + return 0xFFFFFFFF; /* An error occurred at the disk I/O layer */ +} + + + + +/*-----------------------------------------------------------------------*/ +/* FAT access - Change value of a FAT entry */ +/*-----------------------------------------------------------------------*/ +#if !_FS_READONLY + +FRESULT put_fat ( + FATFS *fs, /* File system object */ + DWORD clst, /* Cluster# to be changed in range of 2 to fs->n_fatent - 1 */ + DWORD val /* New value to mark the cluster */ +) +{ + UINT bc; + BYTE *p; + FRESULT res; + + + if (clst < 2 || clst >= fs->n_fatent) { /* Check range */ + res = FR_INT_ERR; + + } else { + switch (fs->fs_type) { + case FS_FAT12 : + bc = clst; bc += bc / 2; + res = move_window(fs, fs->fatbase + (bc / SS(fs))); + if (res != FR_OK) break; + p = &fs->win[bc % SS(fs)]; + *p = (clst & 1) ? ((*p & 0x0F) | ((BYTE)val << 4)) : (BYTE)val; + bc++; + fs->wflag = 1; + res = move_window(fs, fs->fatbase + (bc / SS(fs))); + if (res != FR_OK) break; + p = &fs->win[bc % SS(fs)]; + *p = (clst & 1) ? (BYTE)(val >> 4) : ((*p & 0xF0) | ((BYTE)(val >> 8) & 0x0F)); + break; + + case FS_FAT16 : + res = move_window(fs, fs->fatbase + (clst / (SS(fs) / 2))); + if (res != FR_OK) break; + p = &fs->win[clst * 2 % SS(fs)]; + ST_WORD(p, (WORD)val); + break; + + case FS_FAT32 : + res = move_window(fs, fs->fatbase + (clst / (SS(fs) / 4))); + if (res != FR_OK) break; + p = &fs->win[clst * 4 % SS(fs)]; + val |= LD_DWORD(p) & 0xF0000000; + ST_DWORD(p, val); + break; + + default : + res = FR_INT_ERR; + } + fs->wflag = 1; + } + + return res; +} +#endif /* !_FS_READONLY */ + + + + +/*-----------------------------------------------------------------------*/ +/* FAT handling - Remove a cluster chain */ +/*-----------------------------------------------------------------------*/ +#if !_FS_READONLY +static +FRESULT remove_chain ( + FATFS *fs, /* File system object */ + DWORD clst /* Cluster# to remove a chain from */ +) +{ + FRESULT res; + DWORD nxt; +#if _USE_ERASE + DWORD scl = clst, ecl = clst, resion[2]; +#endif + + if (clst < 2 || clst >= fs->n_fatent) { /* Check range */ + res = FR_INT_ERR; + + } else { + res = FR_OK; + while (clst < fs->n_fatent) { /* Not a last link? */ + nxt = get_fat(fs, clst); /* Get cluster status */ + if (nxt == 0) break; /* Empty cluster? */ + if (nxt == 1) { res = FR_INT_ERR; break; } /* Internal error? */ + if (nxt == 0xFFFFFFFF) { res = FR_DISK_ERR; break; } /* Disk error? */ + res = put_fat(fs, clst, 0); /* Mark the cluster "empty" */ + if (res != FR_OK) break; + if (fs->free_clust != 0xFFFFFFFF) { /* Update FSInfo */ + fs->free_clust++; + fs->fsi_flag = 1; + } +#if _USE_ERASE + if (ecl + 1 == nxt) { /* Next cluster is contiguous */ + ecl = nxt; + } else { /* End of contiguous clusters */ + resion[0] = clust2sect(fs, scl); /* Start sector */ + resion[1] = clust2sect(fs, ecl) + fs->csize - 1; /* End sector */ + disk_ioctl(fs->drv, CTRL_ERASE_SECTOR, resion); /* Erase the block */ + scl = ecl = nxt; + } +#endif + clst = nxt; /* Next cluster */ + } + } + + return res; +} +#endif + + + + +/*-----------------------------------------------------------------------*/ +/* FAT handling - Stretch or Create a cluster chain */ +/*-----------------------------------------------------------------------*/ +#if !_FS_READONLY +static +DWORD create_chain ( /* 0:No free cluster, 1:Internal error, 0xFFFFFFFF:Disk error, >=2:New cluster# */ + FATFS *fs, /* File system object */ + DWORD clst /* Cluster# to stretch. 0 means create a new chain. */ +) +{ + DWORD cs, ncl, scl; + FRESULT res; + + + if (clst == 0) { /* Create a new chain */ + scl = fs->last_clust; /* Get suggested start point */ + if (!scl || scl >= fs->n_fatent) scl = 1; + } + else { /* Stretch the current chain */ + cs = get_fat(fs, clst); /* Check the cluster status */ + if (cs < 2) return 1; /* It is an invalid cluster */ + if (cs < fs->n_fatent) return cs; /* It is already followed by next cluster */ + scl = clst; + } + + ncl = scl; /* Start cluster */ + for (;;) { + ncl++; /* Next cluster */ + if (ncl >= fs->n_fatent) { /* Wrap around */ + ncl = 2; + if (ncl > scl) return 0; /* No free cluster */ + } + cs = get_fat(fs, ncl); /* Get the cluster status */ + if (cs == 0) break; /* Found a free cluster */ + if (cs == 0xFFFFFFFF || cs == 1)/* An error occurred */ + return cs; + if (ncl == scl) return 0; /* No free cluster */ + } + + res = put_fat(fs, ncl, 0x0FFFFFFF); /* Mark the new cluster "last link" */ + if (res == FR_OK && clst != 0) { + res = put_fat(fs, clst, ncl); /* Link it to the previous one if needed */ + } + if (res == FR_OK) { + fs->last_clust = ncl; /* Update FSINFO */ + if (fs->free_clust != 0xFFFFFFFF) { + fs->free_clust--; + fs->fsi_flag = 1; + } + } else { + ncl = (res == FR_DISK_ERR) ? 0xFFFFFFFF : 1; + } + + return ncl; /* Return new cluster number or error code */ +} +#endif /* !_FS_READONLY */ + + + + +/*-----------------------------------------------------------------------*/ +/* Directory handling - Set directory index */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT dir_sdi ( + DIR *dj, /* Pointer to directory object */ + WORD idx /* Directory index number */ +) +{ + DWORD clst; + WORD ic; + + + dj->index = idx; + clst = dj->sclust; + if (clst == 1 || clst >= dj->fs->n_fatent) /* Check start cluster range */ + return FR_INT_ERR; + if (!clst && dj->fs->fs_type == FS_FAT32) /* Replace cluster# 0 with root cluster# if in FAT32 */ + clst = dj->fs->dirbase; + + if (clst == 0) { /* Static table (root-dir in FAT12/16) */ + dj->clust = clst; + if (idx >= dj->fs->n_rootdir) /* Index is out of range */ + return FR_INT_ERR; + dj->sect = dj->fs->dirbase + idx / (SS(dj->fs) / 32); /* Sector# */ + } + else { /* Dynamic table (sub-dirs or root-dir in FAT32) */ + ic = SS(dj->fs) / 32 * dj->fs->csize; /* Entries per cluster */ + while (idx >= ic) { /* Follow cluster chain */ + clst = get_fat(dj->fs, clst); /* Get next cluster */ + if (clst == 0xFFFFFFFF) return FR_DISK_ERR; /* Disk error */ + if (clst < 2 || clst >= dj->fs->n_fatent) /* Reached to end of table or int error */ + return FR_INT_ERR; + idx -= ic; + } + dj->clust = clst; + dj->sect = clust2sect(dj->fs, clst) + idx / (SS(dj->fs) / 32); /* Sector# */ + } + + dj->dir = dj->fs->win + (idx % (SS(dj->fs) / 32)) * 32; /* Ptr to the entry in the sector */ + + return FR_OK; /* Seek succeeded */ +} + + + + +/*-----------------------------------------------------------------------*/ +/* Directory handling - Move directory index next */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT dir_next ( /* FR_OK:Succeeded, FR_NO_FILE:End of table, FR_DENIED:EOT and could not stretch */ + DIR *dj, /* Pointer to directory object */ + int stretch /* 0: Do not stretch table, 1: Stretch table if needed */ +) +{ + DWORD clst; + WORD i; + + + i = dj->index + 1; + if (!i || !dj->sect) /* Report EOT when index has reached 65535 */ + return FR_NO_FILE; + + if (!(i % (SS(dj->fs) / 32))) { /* Sector changed? */ + dj->sect++; /* Next sector */ + + if (dj->clust == 0) { /* Static table */ + if (i >= dj->fs->n_rootdir) /* Report EOT when end of table */ + return FR_NO_FILE; + } + else { /* Dynamic table */ + if (((i / (SS(dj->fs) / 32)) & (dj->fs->csize - 1)) == 0) { /* Cluster changed? */ + clst = get_fat(dj->fs, dj->clust); /* Get next cluster */ + if (clst <= 1) return FR_INT_ERR; + if (clst == 0xFFFFFFFF) return FR_DISK_ERR; + if (clst >= dj->fs->n_fatent) { /* When it reached end of dynamic table */ +#if !_FS_READONLY + BYTE c; + if (!stretch) return FR_NO_FILE; /* When do not stretch, report EOT */ + clst = create_chain(dj->fs, dj->clust); /* Stretch cluster chain */ + if (clst == 0) return FR_DENIED; /* No free cluster */ + if (clst == 1) return FR_INT_ERR; + if (clst == 0xFFFFFFFF) return FR_DISK_ERR; + /* Clean-up stretched table */ + if (move_window(dj->fs, 0)) return FR_DISK_ERR; /* Flush active window */ + mem_set(dj->fs->win, 0, SS(dj->fs)); /* Clear window buffer */ + dj->fs->winsect = clust2sect(dj->fs, clst); /* Cluster start sector */ + for (c = 0; c < dj->fs->csize; c++) { /* Fill the new cluster with 0 */ + dj->fs->wflag = 1; + if (move_window(dj->fs, 0)) return FR_DISK_ERR; + dj->fs->winsect++; + } + dj->fs->winsect -= c; /* Rewind window address */ +#else + return FR_NO_FILE; /* Report EOT */ +#endif + } + dj->clust = clst; /* Initialize data for new cluster */ + dj->sect = clust2sect(dj->fs, clst); + } + } + } + + dj->index = i; + dj->dir = dj->fs->win + (i % (SS(dj->fs) / 32)) * 32; + + return FR_OK; +} + + + + +/*-----------------------------------------------------------------------*/ +/* LFN handling - Test/Pick/Fit an LFN segment from/to directory entry */ +/*-----------------------------------------------------------------------*/ +#if _USE_LFN +static +const BYTE LfnOfs[] = {1,3,5,7,9,14,16,18,20,22,24,28,30}; /* Offset of LFN chars in the directory entry */ + + +static +int cmp_lfn ( /* 1:Matched, 0:Not matched */ + WCHAR *lfnbuf, /* Pointer to the LFN to be compared */ + BYTE *dir /* Pointer to the directory entry containing a part of LFN */ +) +{ + UINT i, s; + WCHAR wc, uc; + + + i = ((dir[LDIR_Ord] & 0xBF) - 1) * 13; /* Get offset in the LFN buffer */ + s = 0; wc = 1; + do { + uc = LD_WORD(dir+LfnOfs[s]); /* Pick an LFN character from the entry */ + if (wc) { /* Last char has not been processed */ + wc = ff_wtoupper(uc); /* Convert it to upper case */ + if (i >= _MAX_LFN || wc != ff_wtoupper(lfnbuf[i++])) /* Compare it */ + return 0; /* Not matched */ + } else { + if (uc != 0xFFFF) return 0; /* Check filler */ + } + } while (++s < 13); /* Repeat until all chars in the entry are checked */ + + if ((dir[LDIR_Ord] & 0x40) && wc && lfnbuf[i]) /* Last segment matched but different length */ + return 0; + + return 1; /* The part of LFN matched */ +} + + + +static +int pick_lfn ( /* 1:Succeeded, 0:Buffer overflow */ + WCHAR *lfnbuf, /* Pointer to the Unicode-LFN buffer */ + BYTE *dir /* Pointer to the directory entry */ +) +{ + UINT i, s; + WCHAR wc, uc; + + + i = ((dir[LDIR_Ord] & 0x3F) - 1) * 13; /* Offset in the LFN buffer */ + + s = 0; wc = 1; + do { + uc = LD_WORD(dir+LfnOfs[s]); /* Pick an LFN character from the entry */ + if (wc) { /* Last char has not been processed */ + if (i >= _MAX_LFN) return 0; /* Buffer overflow? */ + lfnbuf[i++] = wc = uc; /* Store it */ + } else { + if (uc != 0xFFFF) return 0; /* Check filler */ + } + } while (++s < 13); /* Read all character in the entry */ + + if (dir[LDIR_Ord] & 0x40) { /* Put terminator if it is the last LFN part */ + if (i >= _MAX_LFN) return 0; /* Buffer overflow? */ + lfnbuf[i] = 0; + } + + return 1; +} + + +#if !_FS_READONLY +static +void fit_lfn ( + const WCHAR *lfnbuf, /* Pointer to the LFN buffer */ + BYTE *dir, /* Pointer to the directory entry */ + BYTE ord, /* LFN order (1-20) */ + BYTE sum /* SFN sum */ +) +{ + UINT i, s; + WCHAR wc; + + + dir[LDIR_Chksum] = sum; /* Set check sum */ + dir[LDIR_Attr] = AM_LFN; /* Set attribute. LFN entry */ + dir[LDIR_Type] = 0; + ST_WORD(dir+LDIR_FstClusLO, 0); + + i = (ord - 1) * 13; /* Get offset in the LFN buffer */ + s = wc = 0; + do { + if (wc != 0xFFFF) wc = lfnbuf[i++]; /* Get an effective char */ + ST_WORD(dir+LfnOfs[s], wc); /* Put it */ + if (!wc) wc = 0xFFFF; /* Padding chars following last char */ + } while (++s < 13); + if (wc == 0xFFFF || !lfnbuf[i]) ord |= 0x40; /* Bottom LFN part is the start of LFN sequence */ + dir[LDIR_Ord] = ord; /* Set the LFN order */ +} + +#endif +#endif + + + +/*-----------------------------------------------------------------------*/ +/* Create numbered name */ +/*-----------------------------------------------------------------------*/ +#if _USE_LFN +void gen_numname ( + BYTE *dst, /* Pointer to generated SFN */ + const BYTE *src, /* Pointer to source SFN to be modified */ + const WCHAR *lfn, /* Pointer to LFN */ + WORD seq /* Sequence number */ +) +{ + BYTE ns[8], c; + UINT i, j; + + + mem_cpy(dst, src, 11); + + if (seq > 5) { /* On many collisions, generate a hash number instead of sequential number */ + do seq = (seq >> 1) + (seq << 15) + (WORD)*lfn++; while (*lfn); + } + + /* itoa */ + i = 7; + do { + c = (seq % 16) + '0'; + if (c > '9') c += 7; + ns[i--] = c; + seq /= 16; + } while (seq); + ns[i] = '~'; + + /* Append the number */ + for (j = 0; j < i && dst[j] != ' '; j++) { + if (IsDBCS1(dst[j])) { + if (j == i - 1) break; + j++; + } + } + do { + dst[j++] = (i < 8) ? ns[i++] : ' '; + } while (j < 8); +} +#endif + + + + +/*-----------------------------------------------------------------------*/ +/* Calculate sum of an SFN */ +/*-----------------------------------------------------------------------*/ +#if _USE_LFN +static +BYTE sum_sfn ( + const BYTE *dir /* Ptr to directory entry */ +) +{ + BYTE sum = 0; + UINT n = 11; + + do sum = (sum >> 1) + (sum << 7) + *dir++; while (--n); + return sum; +} +#endif + + + + +/*-----------------------------------------------------------------------*/ +/* Directory handling - Find an object in the directory */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT dir_find ( + DIR *dj /* Pointer to the directory object linked to the file name */ +) +{ + FRESULT res; + BYTE c, *dir; +#if _USE_LFN + BYTE a, ord, sum; +#endif + + res = dir_sdi(dj, 0); /* Rewind directory object */ + if (res != FR_OK) return res; + +#if _USE_LFN + ord = sum = 0xFF; +#endif + do { + res = move_window(dj->fs, dj->sect); + if (res != FR_OK) break; + dir = dj->dir; /* Ptr to the directory entry of current index */ + c = dir[DIR_Name]; + if (c == 0) { res = FR_NO_FILE; break; } /* Reached to end of table */ +#if _USE_LFN /* LFN configuration */ + a = dir[DIR_Attr] & AM_MASK; + if (c == 0xE5 || ((a & AM_VOL) && a != AM_LFN)) { /* An entry without valid data */ + ord = 0xFF; + } else { + if (a == AM_LFN) { /* An LFN entry is found */ + if (dj->lfn) { + if (c & 0x40) { /* Is it start of LFN sequence? */ + sum = dir[LDIR_Chksum]; + c &= 0xBF; ord = c; /* LFN start order */ + dj->lfn_idx = dj->index; + } + /* Check validity of the LFN entry and compare it with given name */ + ord = (c == ord && sum == dir[LDIR_Chksum] && cmp_lfn(dj->lfn, dir)) ? ord - 1 : 0xFF; + } + } else { /* An SFN entry is found */ + if (!ord && sum == sum_sfn(dir)) break; /* LFN matched? */ + ord = 0xFF; dj->lfn_idx = 0xFFFF; /* Reset LFN sequence */ + if (!(dj->fn[NS] & NS_LOSS) && !mem_cmp(dir, dj->fn, 11)) break; /* SFN matched? */ + } + } +#else /* Non LFN configuration */ + if (!(dir[DIR_Attr] & AM_VOL) && !mem_cmp(dir, dj->fn, 11)) /* Is it a valid entry? */ + break; +#endif + res = dir_next(dj, 0); /* Next entry */ + } while (res == FR_OK); + + return res; +} + + + + +/*-----------------------------------------------------------------------*/ +/* Read an object from the directory */ +/*-----------------------------------------------------------------------*/ +#if _FS_MINIMIZE <= 1 +static +FRESULT dir_read ( + DIR *dj /* Pointer to the directory object that pointing the entry to be read */ +) +{ + FRESULT res; + BYTE c, *dir; +#if _USE_LFN + BYTE a, ord = 0xFF, sum = 0xFF; +#endif + + res = FR_NO_FILE; + while (dj->sect) { + res = move_window(dj->fs, dj->sect); + if (res != FR_OK) break; + dir = dj->dir; /* Ptr to the directory entry of current index */ + c = dir[DIR_Name]; + if (c == 0) { res = FR_NO_FILE; break; } /* Reached to end of table */ +#if _USE_LFN /* LFN configuration */ + a = dir[DIR_Attr] & AM_MASK; + if (c == 0xE5 || (!_FS_RPATH && c == '.') || ((a & AM_VOL) && a != AM_LFN)) { /* An entry without valid data */ + ord = 0xFF; + } else { + if (a == AM_LFN) { /* An LFN entry is found */ + if (c & 0x40) { /* Is it start of LFN sequence? */ + sum = dir[LDIR_Chksum]; + c &= 0xBF; ord = c; + dj->lfn_idx = dj->index; + } + /* Check LFN validity and capture it */ + ord = (c == ord && sum == dir[LDIR_Chksum] && pick_lfn(dj->lfn, dir)) ? ord - 1 : 0xFF; + } else { /* An SFN entry is found */ + if (ord || sum != sum_sfn(dir)) /* Is there a valid LFN? */ + dj->lfn_idx = 0xFFFF; /* It has no LFN. */ + break; + } + } +#else /* Non LFN configuration */ + if (c != 0xE5 && (_FS_RPATH || c != '.') && !(dir[DIR_Attr] & AM_VOL)) /* Is it a valid entry? */ + break; +#endif + res = dir_next(dj, 0); /* Next entry */ + if (res != FR_OK) break; + } + + if (res != FR_OK) dj->sect = 0; + + return res; +} +#endif + + + +/*-----------------------------------------------------------------------*/ +/* Register an object to the directory */ +/*-----------------------------------------------------------------------*/ +#if !_FS_READONLY +static +FRESULT dir_register ( /* FR_OK:Successful, FR_DENIED:No free entry or too many SFN collision, FR_DISK_ERR:Disk error */ + DIR *dj /* Target directory with object name to be created */ +) +{ + FRESULT res; + BYTE c, *dir; +#if _USE_LFN /* LFN configuration */ + WORD n, ne, is; + BYTE sn[12], *fn, sum; + WCHAR *lfn; + + + fn = dj->fn; lfn = dj->lfn; + mem_cpy(sn, fn, 12); + + if (_FS_RPATH && (sn[NS] & NS_DOT)) /* Cannot create dot entry */ + return FR_INVALID_NAME; + + if (sn[NS] & NS_LOSS) { /* When LFN is out of 8.3 format, generate a numbered name */ + fn[NS] = 0; dj->lfn = 0; /* Find only SFN */ + for (n = 1; n < 100; n++) { + gen_numname(fn, sn, lfn, n); /* Generate a numbered name */ + res = dir_find(dj); /* Check if the name collides with existing SFN */ + if (res != FR_OK) break; + } + if (n == 100) return FR_DENIED; /* Abort if too many collisions */ + if (res != FR_NO_FILE) return res; /* Abort if the result is other than 'not collided' */ + fn[NS] = sn[NS]; dj->lfn = lfn; + } + + if (sn[NS] & NS_LFN) { /* When LFN is to be created, reserve an SFN + LFN entries. */ + for (ne = 0; lfn[ne]; ne++) ; + ne = (ne + 25) / 13; + } else { /* Otherwise reserve only an SFN entry. */ + ne = 1; + } + + /* Reserve contiguous entries */ + res = dir_sdi(dj, 0); + if (res != FR_OK) return res; + n = is = 0; + do { + res = move_window(dj->fs, dj->sect); + if (res != FR_OK) break; + c = *dj->dir; /* Check the entry status */ + if (c == 0xE5 || c == 0) { /* Is it a blank entry? */ + if (n == 0) is = dj->index; /* First index of the contiguous entry */ + if (++n == ne) break; /* A contiguous entry that required count is found */ + } else { + n = 0; /* Not a blank entry. Restart to search */ + } + res = dir_next(dj, 1); /* Next entry with table stretch */ + } while (res == FR_OK); + + if (res == FR_OK && ne > 1) { /* Initialize LFN entry if needed */ + res = dir_sdi(dj, is); + if (res == FR_OK) { + sum = sum_sfn(dj->fn); /* Sum of the SFN tied to the LFN */ + ne--; + do { /* Store LFN entries in bottom first */ + res = move_window(dj->fs, dj->sect); + if (res != FR_OK) break; + fit_lfn(dj->lfn, dj->dir, (BYTE)ne, sum); + dj->fs->wflag = 1; + res = dir_next(dj, 0); /* Next entry */ + } while (res == FR_OK && --ne); + } + } + +#else /* Non LFN configuration */ + res = dir_sdi(dj, 0); + if (res == FR_OK) { + do { /* Find a blank entry for the SFN */ + res = move_window(dj->fs, dj->sect); + if (res != FR_OK) break; + c = *dj->dir; + if (c == 0xE5 || c == 0) break; /* Is it a blank entry? */ + res = dir_next(dj, 1); /* Next entry with table stretch */ + } while (res == FR_OK); + } +#endif + + if (res == FR_OK) { /* Initialize the SFN entry */ + res = move_window(dj->fs, dj->sect); + if (res == FR_OK) { + dir = dj->dir; + mem_set(dir, 0, 32); /* Clean the entry */ + mem_cpy(dir, dj->fn, 11); /* Put SFN */ +#if _USE_LFN + dir[DIR_NTres] = *(dj->fn+NS) & (NS_BODY | NS_EXT); /* Put NT flag */ +#endif + dj->fs->wflag = 1; + } + } + + return res; +} +#endif /* !_FS_READONLY */ + + + + +/*-----------------------------------------------------------------------*/ +/* Remove an object from the directory */ +/*-----------------------------------------------------------------------*/ +#if !_FS_READONLY && !_FS_MINIMIZE +static +FRESULT dir_remove ( /* FR_OK: Successful, FR_DISK_ERR: A disk error */ + DIR *dj /* Directory object pointing the entry to be removed */ +) +{ + FRESULT res; +#if _USE_LFN /* LFN configuration */ + WORD i; + + i = dj->index; /* SFN index */ + res = dir_sdi(dj, (WORD)((dj->lfn_idx == 0xFFFF) ? i : dj->lfn_idx)); /* Goto the SFN or top of the LFN entries */ + if (res == FR_OK) { + do { + res = move_window(dj->fs, dj->sect); + if (res != FR_OK) break; + *dj->dir = 0xE5; /* Mark the entry "deleted" */ + dj->fs->wflag = 1; + if (dj->index >= i) break; /* When reached SFN, all entries of the object has been deleted. */ + res = dir_next(dj, 0); /* Next entry */ + } while (res == FR_OK); + if (res == FR_NO_FILE) res = FR_INT_ERR; + } + +#else /* Non LFN configuration */ + res = dir_sdi(dj, dj->index); + if (res == FR_OK) { + res = move_window(dj->fs, dj->sect); + if (res == FR_OK) { + *dj->dir = 0xE5; /* Mark the entry "deleted" */ + dj->fs->wflag = 1; + } + } +#endif + + return res; +} +#endif /* !_FS_READONLY */ + + + + +/*-----------------------------------------------------------------------*/ +/* Pick a segment and create the object name in directory form */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT create_name ( + DIR *dj, /* Pointer to the directory object */ + const TCHAR **path /* Pointer to pointer to the segment in the path string */ +) +{ +#ifdef _EXCVT + static const BYTE excvt[] = _EXCVT; /* Upper conversion table for extended chars */ +#endif + +#if _USE_LFN /* LFN configuration */ + BYTE b, cf; + WCHAR w, *lfn; + UINT i, ni, si, di; + const TCHAR *p; + + /* Create LFN in Unicode */ + si = di = 0; + p = *path; + lfn = dj->lfn; + for (;;) { + w = p[si++]; /* Get a character */ + if (w < ' ' || w == '/' || w == '\\') break; /* Break on end of segment */ + if (di >= _MAX_LFN) /* Reject too long name */ + return FR_INVALID_NAME; +#if !_LFN_UNICODE + w &= 0xFF; + if (IsDBCS1(w)) { /* Check if it is a DBC 1st byte (always false on SBCS cfg) */ + b = (BYTE)p[si++]; /* Get 2nd byte */ + if (!IsDBCS2(b)) + return FR_INVALID_NAME; /* Reject invalid sequence */ + w = (w << 8) + b; /* Create a DBC */ + } + w = ff_convert(w, 1); /* Convert ANSI/OEM to Unicode */ + if (!w) return FR_INVALID_NAME; /* Reject invalid code */ +#endif + if (w < 0x80 && chk_chr("\"*:<>\?|\x7F", w)) /* Reject illegal chars for LFN */ + return FR_INVALID_NAME; + lfn[di++] = w; /* Store the Unicode char */ + } + *path = &p[si]; /* Return pointer to the next segment */ + cf = (w < ' ') ? NS_LAST : 0; /* Set last segment flag if end of path */ +#if _FS_RPATH + if ((di == 1 && lfn[di-1] == '.') || /* Is this a dot entry? */ + (di == 2 && lfn[di-1] == '.' && lfn[di-2] == '.')) { + lfn[di] = 0; + for (i = 0; i < 11; i++) + dj->fn[i] = (i < di) ? '.' : ' '; + dj->fn[i] = cf | NS_DOT; /* This is a dot entry */ + return FR_OK; + } +#endif + while (di) { /* Strip trailing spaces and dots */ + w = lfn[di-1]; + if (w != ' ' && w != '.') break; + di--; + } + if (!di) return FR_INVALID_NAME; /* Reject nul string */ + + lfn[di] = 0; /* LFN is created */ + + /* Create SFN in directory form */ + mem_set(dj->fn, ' ', 11); + for (si = 0; lfn[si] == ' ' || lfn[si] == '.'; si++) ; /* Strip leading spaces and dots */ + if (si) cf |= NS_LOSS | NS_LFN; + while (di && lfn[di - 1] != '.') di--; /* Find extension (di<=si: no extension) */ + + b = i = 0; ni = 8; + for (;;) { + w = lfn[si++]; /* Get an LFN char */ + if (!w) break; /* Break on end of the LFN */ + if (w == ' ' || (w == '.' && si != di)) { /* Remove spaces and dots */ + cf |= NS_LOSS | NS_LFN; continue; + } + + if (i >= ni || si == di) { /* Extension or end of SFN */ + if (ni == 11) { /* Long extension */ + cf |= NS_LOSS | NS_LFN; break; + } + if (si != di) cf |= NS_LOSS | NS_LFN; /* Out of 8.3 format */ + if (si > di) break; /* No extension */ + si = di; i = 8; ni = 11; /* Enter extension section */ + b <<= 2; continue; + } + + if (w >= 0x80) { /* Non ASCII char */ +#ifdef _EXCVT + w = ff_convert(w, 0); /* Unicode -> OEM code */ + if (w) w = excvt[w - 0x80]; /* Convert extended char to upper (SBCS) */ +#else + w = ff_convert(ff_wtoupper(w), 0); /* Upper converted Unicode -> OEM code */ +#endif + cf |= NS_LFN; /* Force create LFN entry */ + } + + if (_DF1S && w >= 0x100) { /* Double byte char (always false on SBCS cfg) */ + if (i >= ni - 1) { + cf |= NS_LOSS | NS_LFN; i = ni; continue; + } + dj->fn[i++] = (BYTE)(w >> 8); + } else { /* Single byte char */ + if (!w || chk_chr("+,;=[]", w)) { /* Replace illegal chars for SFN */ + w = '_'; cf |= NS_LOSS | NS_LFN;/* Lossy conversion */ + } else { + if (IsUpper(w)) { /* ASCII large capital */ + b |= 2; + } else { + if (IsLower(w)) { /* ASCII small capital */ + b |= 1; w -= 0x20; + } + } + } + } + dj->fn[i++] = (BYTE)w; + } + + if (dj->fn[0] == 0xE5) dj->fn[0] = 0x05; /* If the first char collides with deleted mark, replace it with 0x05 */ + + if (ni == 8) b <<= 2; + if ((b & 0x0C) == 0x0C || (b & 0x03) == 0x03) /* Create LFN entry when there are composite capitals */ + cf |= NS_LFN; + if (!(cf & NS_LFN)) { /* When LFN is in 8.3 format without extended char, NT flags are created */ + if ((b & 0x03) == 0x01) cf |= NS_EXT; /* NT flag (Extension has only small capital) */ + if ((b & 0x0C) == 0x04) cf |= NS_BODY; /* NT flag (Filename has only small capital) */ + } + + dj->fn[NS] = cf; /* SFN is created */ + + return FR_OK; + + +#else /* Non-LFN configuration */ + BYTE b, c, d, *sfn; + UINT ni, si, i; + const char *p; + + /* Create file name in directory form */ + sfn = dj->fn; + mem_set(sfn, ' ', 11); + si = i = b = 0; ni = 8; + p = *path; +#if _FS_RPATH + if (p[si] == '.') { /* Is this a dot entry? */ + for (;;) { + c = (BYTE)p[si++]; + if (c != '.' || si >= 3) break; + sfn[i++] = c; + } + if (c != '/' && c != '\\' && c > ' ') return FR_INVALID_NAME; + *path = &p[si]; /* Return pointer to the next segment */ + sfn[NS] = (c <= ' ') ? NS_LAST | NS_DOT : NS_DOT; /* Set last segment flag if end of path */ + return FR_OK; + } +#endif + for (;;) { + c = (BYTE)p[si++]; + if (c <= ' ' || c == '/' || c == '\\') break; /* Break on end of segment */ + if (c == '.' || i >= ni) { + if (ni != 8 || c != '.') return FR_INVALID_NAME; + i = 8; ni = 11; + b <<= 2; continue; + } + if (c >= 0x80) { /* Extended char? */ + b |= 3; /* Eliminate NT flag */ +#ifdef _EXCVT + c = excvt[c-0x80]; /* Upper conversion (SBCS) */ +#else +#if !_DF1S /* ASCII only cfg */ + return FR_INVALID_NAME; +#endif +#endif + } + if (IsDBCS1(c)) { /* Check if it is a DBC 1st byte (always false on SBCS cfg) */ + d = (BYTE)p[si++]; /* Get 2nd byte */ + if (!IsDBCS2(d) || i >= ni - 1) /* Reject invalid DBC */ + return FR_INVALID_NAME; + sfn[i++] = c; + sfn[i++] = d; + } else { /* Single byte code */ + if (chk_chr("\"*+,:;<=>\?[]|\x7F", c)) /* Reject illegal chrs for SFN */ + return FR_INVALID_NAME; + if (IsUpper(c)) { /* ASCII large capital? */ + b |= 2; + } else { + if (IsLower(c)) { /* ASCII small capital? */ + b |= 1; c -= 0x20; + } + } + sfn[i++] = c; + } + } + *path = &p[si]; /* Return pointer to the next segment */ + c = (c <= ' ') ? NS_LAST : 0; /* Set last segment flag if end of path */ + + if (!i) return FR_INVALID_NAME; /* Reject nul string */ + if (sfn[0] == 0xE5) sfn[0] = 0x05; /* When first char collides with 0xE5, replace it with 0x05 */ + + if (ni == 8) b <<= 2; + if ((b & 0x03) == 0x01) c |= NS_EXT; /* NT flag (Name extension has only small capital) */ + if ((b & 0x0C) == 0x04) c |= NS_BODY; /* NT flag (Name body has only small capital) */ + + sfn[NS] = c; /* Store NT flag, File name is created */ + + return FR_OK; +#endif +} + + + + +/*-----------------------------------------------------------------------*/ +/* Get file information from directory entry */ +/*-----------------------------------------------------------------------*/ +#if _FS_MINIMIZE <= 1 +static +void get_fileinfo ( /* No return code */ + DIR *dj, /* Pointer to the directory object */ + FILINFO *fno /* Pointer to the file information to be filled */ +) +{ + UINT i; + BYTE nt, *dir; + TCHAR *p, c; + + + p = fno->fname; + if (dj->sect) { + dir = dj->dir; + nt = dir[DIR_NTres]; /* NT flag */ + for (i = 0; i < 8; i++) { /* Copy name body */ + c = dir[i]; + if (c == ' ') break; + if (c == 0x05) c = (TCHAR)0xE5; + if (_USE_LFN && (nt & NS_BODY) && IsUpper(c)) c += 0x20; +#if _LFN_UNICODE + if (IsDBCS1(c) && i < 7 && IsDBCS2(dir[i+1])) + c = (c << 8) | dir[++i]; + c = ff_convert(c, 1); + if (!c) c = '?'; +#endif + *p++ = c; + } + if (dir[8] != ' ') { /* Copy name extension */ + *p++ = '.'; + for (i = 8; i < 11; i++) { + c = dir[i]; + if (c == ' ') break; + if (_USE_LFN && (nt & NS_EXT) && IsUpper(c)) c += 0x20; +#if _LFN_UNICODE + if (IsDBCS1(c) && i < 10 && IsDBCS2(dir[i+1])) + c = (c << 8) | dir[++i]; + c = ff_convert(c, 1); + if (!c) c = '?'; +#endif + *p++ = c; + } + } + fno->fattrib = dir[DIR_Attr]; /* Attribute */ + fno->fsize = LD_DWORD(dir+DIR_FileSize); /* Size */ + fno->fdate = LD_WORD(dir+DIR_WrtDate); /* Date */ + fno->ftime = LD_WORD(dir+DIR_WrtTime); /* Time */ + } + *p = 0; /* Terminate SFN str by a \0 */ + +#if _USE_LFN + if (fno->lfname && fno->lfsize) { + TCHAR *tp = fno->lfname; + WCHAR w, *lfn; + + i = 0; + if (dj->sect && dj->lfn_idx != 0xFFFF) {/* Get LFN if available */ + lfn = dj->lfn; + while ((w = *lfn++) != 0) { /* Get an LFN char */ +#if !_LFN_UNICODE + w = ff_convert(w, 0); /* Unicode -> OEM conversion */ + if (!w) { i = 0; break; } /* Could not convert, no LFN */ + if (_DF1S && w >= 0x100) /* Put 1st byte if it is a DBC (always false on SBCS cfg) */ + tp[i++] = (TCHAR)(w >> 8); +#endif + if (i >= fno->lfsize - 1) { i = 0; break; } /* Buffer overflow, no LFN */ + tp[i++] = (TCHAR)w; + } + } + tp[i] = 0; /* Terminate the LFN str by a \0 */ + } +#endif +} +#endif /* _FS_MINIMIZE <= 1 */ + + + + +/*-----------------------------------------------------------------------*/ +/* Follow a file path */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT follow_path ( /* FR_OK(0): successful, !=0: error code */ + DIR *dj, /* Directory object to return last directory and found object */ + const TCHAR *path /* Full-path string to find a file or directory */ +) +{ + FRESULT res; + BYTE *dir, ns; + + +#if _FS_RPATH + if (*path == '/' || *path == '\\') { /* There is a heading separator */ + path++; dj->sclust = 0; /* Strip it and start from the root dir */ + } else { /* No heading separator */ + dj->sclust = dj->fs->cdir; /* Start from the current dir */ + } +#else + if (*path == '/' || *path == '\\') /* Strip heading separator if exist */ + path++; + dj->sclust = 0; /* Start from the root dir */ +#endif + + if ((UINT)*path < ' ') { /* Nul path means the start directory itself */ + res = dir_sdi(dj, 0); + dj->dir = 0; + + } else { /* Follow path */ + for (;;) { + res = create_name(dj, &path); /* Get a segment */ + if (res != FR_OK) break; + res = dir_find(dj); /* Find it */ + ns = *(dj->fn+NS); + if (res != FR_OK) { /* Failed to find the object */ + if (res != FR_NO_FILE) break; /* Abort if any hard error occured */ + /* Object not found */ + if (_FS_RPATH && (ns & NS_DOT)) { /* If dot entry is not exit */ + dj->sclust = 0; dj->dir = 0; /* It is the root dir */ + res = FR_OK; + if (!(ns & NS_LAST)) continue; + } else { /* Could not find the object */ + if (!(ns & NS_LAST)) res = FR_NO_PATH; + } + break; + } + if (ns & NS_LAST) break; /* Last segment match. Function completed. */ + dir = dj->dir; /* There is next segment. Follow the sub directory */ + if (!(dir[DIR_Attr] & AM_DIR)) { /* Cannot follow because it is a file */ + res = FR_NO_PATH; break; + } + dj->sclust = LD_CLUST(dir); + } + } + + return res; +} + + + + +/*-----------------------------------------------------------------------*/ +/* Load boot record and check if it is an FAT boot record */ +/*-----------------------------------------------------------------------*/ + +static +BYTE check_fs ( /* 0:The FAT BR, 1:Valid BR but not an FAT, 2:Not a BR, 3:Disk error */ + FATFS *fs, /* File system object */ + DWORD sect /* Sector# (lba) to check if it is an FAT boot record or not */ +) +{ + if (disk_read(fs->drv, fs->win, sect, 1) != RES_OK) { /* Load boot record */ + return 3; + } + + if (LD_WORD(&fs->win[BS_55AA]) != 0xAA55) { /* Check record signature (always placed at offset 510 even if the sector size is >512) */ + return 2; + } + + if ((LD_DWORD(&fs->win[BS_FilSysType]) & 0xFFFFFF) == 0x544146) /* Check "FAT" string */ + return 0; + if ((LD_DWORD(&fs->win[BS_FilSysType32]) & 0xFFFFFF) == 0x544146) + return 0; + + return 1; +} + + + + +/*-----------------------------------------------------------------------*/ +/* Check if the file system object is valid or not */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT chk_mounted ( /* FR_OK(0): successful, !=0: any error occurred */ + const TCHAR **path, /* Pointer to pointer to the path name (drive number) */ + FATFS **rfs, /* Pointer to pointer to the found file system object */ + BYTE chk_wp /* !=0: Check media write protection for write access */ +) +{ + BYTE fmt, b, *tbl; + UINT vol; + DSTATUS stat; + DWORD bsect, fasize, tsect, sysect, nclst, szbfat; + WORD nrsv; + const TCHAR *p = *path; + FATFS *fs; + + /* Get logical drive number from the path name */ + vol = p[0] - '0'; /* Is there a drive number? */ + if (vol <= 9 && p[1] == ':') { /* Found a drive number, get and strip it */ + p += 2; *path = p; /* Return pointer to the path name */ + } else { /* No drive number is given */ +#if _FS_RPATH + vol = CurrVol; /* Use current drive */ +#else + vol = 0; /* Use drive 0 */ +#endif + } + + /* Check if the logical drive is valid or not */ + if (vol >= _VOLUMES) /* Is the drive number valid? */ + return FR_INVALID_DRIVE; + *rfs = fs = FatFs[vol]; /* Return pointer to the corresponding file system object */ + if (!fs) return FR_NOT_ENABLED; /* Is the file system object available? */ + + ENTER_FF(fs); /* Lock file system */ + + if (fs->fs_type) { /* If the logical drive has been mounted */ + stat = disk_status(fs->drv); + if (!(stat & STA_NOINIT)) { /* and the physical drive is kept initialized (has not been changed), */ +#if !_FS_READONLY + if (chk_wp && (stat & STA_PROTECT)) /* Check write protection if needed */ + return FR_WRITE_PROTECTED; +#endif + return FR_OK; /* The file system object is valid */ + } + } + + /* The logical drive must be mounted. */ + /* Following code attempts to mount a volume. (analyze BPB and initialize the fs object) */ + + fs->fs_type = 0; /* Clear the file system object */ + fs->drv = (BYTE)LD2PD(vol); /* Bind the logical drive and a physical drive */ + stat = disk_initialize(fs->drv); /* Initialize low level disk I/O layer */ + if (stat & STA_NOINIT) /* Check if the initialization succeeded */ + return FR_NOT_READY; /* Failed to initialize due to no media or hard error */ +#if _MAX_SS != 512 /* Get disk sector size (variable sector size cfg only) */ + if (disk_ioctl(fs->drv, GET_SECTOR_SIZE, &fs->ssize) != RES_OK) + return FR_DISK_ERR; +#endif +#if !_FS_READONLY + if (chk_wp && (stat & STA_PROTECT)) /* Check disk write protection if needed */ + return FR_WRITE_PROTECTED; +#endif + /* Search FAT partition on the drive. Supports only generic partitionings, FDISK and SFD. */ + fmt = check_fs(fs, bsect = 0); /* Check sector 0 if it is a VBR */ + if (fmt == 1) { /* Not an FAT-VBR, the disk may be partitioned */ + /* Check the partition listed in top of the partition table */ + tbl = &fs->win[MBR_Table + LD2PT(vol) * 16]; /* Partition table */ + if (tbl[4]) { /* Is the partition existing? */ + bsect = LD_DWORD(&tbl[8]); /* Partition offset in LBA */ + fmt = check_fs(fs, bsect); /* Check the partition */ + } + } + if (fmt == 3) return FR_DISK_ERR; + if (fmt) return FR_NO_FILESYSTEM; /* No FAT volume is found */ + + /* Following code initializes the file system object */ + + if (LD_WORD(fs->win+BPB_BytsPerSec) != SS(fs)) { /* (BPB_BytsPerSec must be equal to the physical sector size) */ + + return FR_NO_FILESYSTEM; + } + + fasize = LD_WORD(fs->win+BPB_FATSz16); /* Number of sectors per FAT */ + if (!fasize) fasize = LD_DWORD(fs->win+BPB_FATSz32); + fs->fsize = fasize; + + fs->n_fats = b = fs->win[BPB_NumFATs]; /* Number of FAT copies */ + if (b != 1 && b != 2) { + return FR_NO_FILESYSTEM; /* (Must be 1 or 2) */ + } + fasize *= b; /* Number of sectors for FAT area */ + + fs->csize = b = fs->win[BPB_SecPerClus]; /* Number of sectors per cluster */ + if (!b || (b & (b - 1))) { + return FR_NO_FILESYSTEM; /* (Must be power of 2) */ + } + + fs->n_rootdir = LD_WORD(fs->win+BPB_RootEntCnt); /* Number of root directory entries */ + if (fs->n_rootdir % (SS(fs) / 32)) { + return FR_NO_FILESYSTEM; /* (BPB_RootEntCnt must be sector aligned) */ + } + + tsect = LD_WORD(fs->win+BPB_TotSec16); /* Number of sectors on the volume */ + if (!tsect) tsect = LD_DWORD(fs->win+BPB_TotSec32); + + nrsv = LD_WORD(fs->win+BPB_RsvdSecCnt); /* Number of reserved sectors */ + if (!nrsv) { + return FR_NO_FILESYSTEM; /* (BPB_RsvdSecCnt must not be 0) */ + } + + /* Determine the FAT sub type */ + sysect = nrsv + fasize + fs->n_rootdir / (SS(fs) / 32); /* RSV+FAT+DIR */ + if (tsect < sysect) { + return FR_NO_FILESYSTEM; /* (Invalid volume size) */ + } + nclst = (tsect - sysect) / fs->csize; /* Number of clusters */ + if (!nclst) { + return FR_NO_FILESYSTEM; /* (Invalid volume size) */ + } + fmt = FS_FAT12; + if (nclst >= MIN_FAT16) fmt = FS_FAT16; + if (nclst >= MIN_FAT32) fmt = FS_FAT32; + + /* Boundaries and Limits */ + fs->n_fatent = nclst + 2; /* Number of FAT entries */ + fs->database = bsect + sysect; /* Data start sector */ + fs->fatbase = bsect + nrsv; /* FAT start sector */ + if (fmt == FS_FAT32) { + if (fs->n_rootdir) { + return FR_NO_FILESYSTEM; /* (BPB_RootEntCnt must be 0) */ + } + fs->dirbase = LD_DWORD(fs->win+BPB_RootClus); /* Root directory start cluster */ + szbfat = fs->n_fatent * 4; /* (Required FAT size) */ + } else { + if (!fs->n_rootdir) { + return FR_NO_FILESYSTEM; /* (BPB_RootEntCnt must not be 0) */ + } + fs->dirbase = fs->fatbase + fasize; /* Root directory start sector */ + szbfat = (fmt == FS_FAT16) ? /* (Required FAT size) */ + fs->n_fatent * 2 : fs->n_fatent * 3 / 2 + (fs->n_fatent & 1); + } + if (fs->fsize < (szbfat + (SS(fs) - 1)) / SS(fs)) { /* (FAT size must not be less than FAT sectors */ + return FR_NO_FILESYSTEM; + } + +#if !_FS_READONLY + /* Initialize cluster allocation information */ + fs->free_clust = 0xFFFFFFFF; + fs->last_clust = 0; + + /* Get fsinfo if available */ + if (fmt == FS_FAT32) { + fs->fsi_flag = 0; + fs->fsi_sector = bsect + LD_WORD(fs->win+BPB_FSInfo); + if (disk_read(fs->drv, fs->win, fs->fsi_sector, 1) == RES_OK && + LD_WORD(fs->win+BS_55AA) == 0xAA55 && + LD_DWORD(fs->win+FSI_LeadSig) == 0x41615252 && + LD_DWORD(fs->win+FSI_StrucSig) == 0x61417272) { + fs->last_clust = LD_DWORD(fs->win+FSI_Nxt_Free); + fs->free_clust = LD_DWORD(fs->win+FSI_Free_Count); + } + } +#endif + fs->fs_type = fmt; /* FAT sub-type */ + fs->id = ++Fsid; /* File system mount ID */ + fs->winsect = 0; /* Invalidate sector cache */ + fs->wflag = 0; +#if _FS_RPATH + fs->cdir = 0; /* Current directory (root dir) */ +#endif +#if _FS_SHARE /* Clear file lock semaphores */ + clear_lock(fs); +#endif + + return FR_OK; +} + + + + +/*-----------------------------------------------------------------------*/ +/* Check if the file/dir object is valid or not */ +/*-----------------------------------------------------------------------*/ + +static +FRESULT validate ( /* FR_OK(0): The object is valid, !=0: Invalid */ + FATFS *fs, /* Pointer to the file system object */ + WORD id /* Member id of the target object to be checked */ +) +{ + if (!fs || !fs->fs_type || fs->id != id) + return FR_INVALID_OBJECT; + + ENTER_FF(fs); /* Lock file system */ + + if (disk_status(fs->drv) & STA_NOINIT) + return FR_NOT_READY; + + return FR_OK; +} + + + + +/*-------------------------------------------------------------------------- + + Public Functions + +--------------------------------------------------------------------------*/ + + + +/*-----------------------------------------------------------------------*/ +/* Mount/Unmount a Logical Drive */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_mount ( + BYTE vol, /* Logical drive number to be mounted/unmounted */ + FATFS *fs /* Pointer to new file system object (NULL for unmount)*/ +) +{ + FATFS *rfs; + + + if (vol >= _VOLUMES) /* Check if the drive number is valid */ + return FR_INVALID_DRIVE; + rfs = FatFs[vol]; /* Get current fs object */ + + if (rfs) { +#if _FS_SHARE + clear_lock(rfs); +#endif +#if _FS_REENTRANT /* Discard sync object of the current volume */ + if (!ff_del_syncobj(rfs->sobj)) return FR_INT_ERR; +#endif + rfs->fs_type = 0; /* Clear old fs object */ + } + + if (fs) { + fs->fs_type = 0; /* Clear new fs object */ +#if _FS_REENTRANT /* Create sync object for the new volume */ + if (!ff_cre_syncobj(vol, &fs->sobj)) return FR_INT_ERR; +#endif + } + FatFs[vol] = fs; /* Register new fs object */ + + return FR_OK; +} + + + + +/*-----------------------------------------------------------------------*/ +/* Open or Create a File */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_open ( + FIL *fp, /* Pointer to the blank file object */ + const TCHAR *path, /* Pointer to the file name */ + BYTE mode /* Access mode and file open mode flags */ +) +{ + FRESULT res; + DIR dj; + BYTE *dir; + DEF_NAMEBUF; + + + fp->fs = 0; /* Clear file object */ + +#if !_FS_READONLY + mode &= FA_READ | FA_WRITE | FA_CREATE_ALWAYS | FA_OPEN_ALWAYS | FA_CREATE_NEW; + res = chk_mounted(&path, &dj.fs, (BYTE)(mode & ~FA_READ)); +#else + mode &= FA_READ; + res = chk_mounted(&path, &dj.fs, 0); +#endif + INIT_BUF(dj); + if (res == FR_OK) + res = follow_path(&dj, path); /* Follow the file path */ + dir = dj.dir; + +#if !_FS_READONLY /* R/W configuration */ + if (res == FR_OK) { + if (!dir) /* Current dir itself */ + res = FR_INVALID_NAME; +#if _FS_SHARE + else + res = chk_lock(&dj, (mode & ~FA_READ) ? 1 : 0); +#endif + } + /* Create or Open a file */ + if (mode & (FA_CREATE_ALWAYS | FA_OPEN_ALWAYS | FA_CREATE_NEW)) { + DWORD dw, cl; + + if (res != FR_OK) { /* No file, create new */ + if (res == FR_NO_FILE) /* There is no file to open, create a new entry */ +#if _FS_SHARE + res = enq_lock(dj.fs) ? dir_register(&dj) : FR_TOO_MANY_OPEN_FILES; +#else + res = dir_register(&dj); +#endif + mode |= FA_CREATE_ALWAYS; /* File is created */ + dir = dj.dir; /* New entry */ + } + else { /* Any object is already existing */ + if (mode & FA_CREATE_NEW) { /* Cannot create new */ + res = FR_EXIST; + } else { + if (dir[DIR_Attr] & (AM_RDO | AM_DIR)) /* Cannot overwrite it (R/O or DIR) */ + res = FR_DENIED; + } + } + if (res == FR_OK && (mode & FA_CREATE_ALWAYS)) { /* Truncate it if overwrite mode */ + dw = get_fattime(); /* Created time */ + ST_DWORD(dir+DIR_CrtTime, dw); + dir[DIR_Attr] = 0; /* Reset attribute */ + ST_DWORD(dir+DIR_FileSize, 0); /* size = 0 */ + cl = LD_CLUST(dir); /* Get start cluster */ + ST_CLUST(dir, 0); /* cluster = 0 */ + dj.fs->wflag = 1; + if (cl) { /* Remove the cluster chain if exist */ + dw = dj.fs->winsect; + res = remove_chain(dj.fs, cl); + if (res == FR_OK) { + dj.fs->last_clust = cl - 1; /* Reuse the cluster hole */ + res = move_window(dj.fs, dw); + } + } + } + } + else { /* Open an existing file */ + if (res == FR_OK) { /* Follow succeeded */ + if (dir[DIR_Attr] & AM_DIR) { /* It is a directory */ + res = FR_NO_FILE; + } else { + if ((mode & FA_WRITE) && (dir[DIR_Attr] & AM_RDO)) /* R/O violation */ + res = FR_DENIED; + } + } + } + if (res == FR_OK) { + if (mode & FA_CREATE_ALWAYS) /* Set file change flag if created or overwritten */ + mode |= FA__WRITTEN; + fp->dir_sect = dj.fs->winsect; /* Pointer to the directory entry */ + fp->dir_ptr = dir; +#if _FS_SHARE + fp->lockid = inc_lock(&dj, (mode & ~FA_READ) ? 1 : 0); + if (!fp->lockid) res = FR_INT_ERR; +#endif + } + +#else /* R/O configuration */ + if (res == FR_OK) { /* Follow succeeded */ + if (!dir) { /* Current dir itself */ + res = FR_INVALID_NAME; + } else { + if (dir[DIR_Attr] & AM_DIR) /* It is a directory */ + res = FR_NO_FILE; + } + } +#endif + FREE_BUF(); + + if (res == FR_OK) { + fp->flag = mode; /* File access mode */ + fp->org_clust = LD_CLUST(dir); /* File start cluster */ + fp->fsize = LD_DWORD(dir+DIR_FileSize); /* File size */ + fp->fptr = 0; /* File pointer */ + fp->dsect = 0; +#if _USE_FASTSEEK + fp->cltbl = 0; /* No cluster link map table */ +#endif + fp->fs = dj.fs; fp->id = dj.fs->id; /* Validate file object */ + } + + LEAVE_FF(dj.fs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Read File */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_read ( + FIL *fp, /* Pointer to the file object */ + void *buff, /* Pointer to data buffer */ + UINT btr, /* Number of bytes to read */ + UINT *br /* Pointer to number of bytes read */ +) +{ + FRESULT res; + DWORD clst, sect, remain; + UINT rcnt, cc; + BYTE csect, *rbuff = (BYTE *)buff; + + *br = 0; /* Initialize byte counter */ + + res = validate(fp->fs, fp->id); /* Check validity of the object */ + if (res != FR_OK) LEAVE_FF(fp->fs, res); + if (fp->flag & FA__ERROR) /* Check abort flag */ + LEAVE_FF(fp->fs, FR_INT_ERR); + if (!(fp->flag & FA_READ)) /* Check access mode */ + LEAVE_FF(fp->fs, FR_DENIED); + remain = fp->fsize - fp->fptr; + if (btr > remain) btr = (UINT)remain; /* Truncate btr by remaining bytes */ + + for ( ; btr; /* Repeat until all data transferred */ + rbuff += rcnt, fp->fptr += rcnt, *br += rcnt, btr -= rcnt) { + if ((fp->fptr % SS(fp->fs)) == 0) { /* On the sector boundary? */ + csect = (BYTE)(fp->fptr / SS(fp->fs) & (fp->fs->csize - 1)); /* Sector offset in the cluster */ + if (!csect) { /* On the cluster boundary? */ + clst = (fp->fptr == 0) ? /* On the top of the file? */ + fp->org_clust : get_fat(fp->fs, fp->curr_clust); + if (clst <= 1) ABORT(fp->fs, FR_INT_ERR); + if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR); + fp->curr_clust = clst; /* Update current cluster */ + } + sect = clust2sect(fp->fs, fp->curr_clust); /* Get current sector */ + if (!sect) ABORT(fp->fs, FR_INT_ERR); + sect += csect; + cc = btr / SS(fp->fs); /* When remaining bytes >= sector size, */ + if (cc) { /* Read maximum contiguous sectors directly */ + if (csect + cc > fp->fs->csize) /* Clip at cluster boundary */ + cc = fp->fs->csize - csect; + if (disk_read(fp->fs->drv, rbuff, sect, (BYTE)cc) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); +#if !_FS_READONLY && _FS_MINIMIZE <= 2 /* Replace one of the read sectors with cached data if it contains a dirty sector */ +#if _FS_TINY + if (fp->fs->wflag && fp->fs->winsect - sect < cc) + mem_cpy(rbuff + ((fp->fs->winsect - sect) * SS(fp->fs)), fp->fs->win, SS(fp->fs)); +#else + if ((fp->flag & FA__DIRTY) && fp->dsect - sect < cc) + mem_cpy(rbuff + ((fp->dsect - sect) * SS(fp->fs)), fp->buf, SS(fp->fs)); +#endif +#endif + rcnt = SS(fp->fs) * cc; /* Number of bytes transferred */ + continue; + } +#if !_FS_TINY +#if !_FS_READONLY + if (fp->flag & FA__DIRTY) { /* Write sector I/O buffer if needed */ + if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); + fp->flag &= ~FA__DIRTY; + } +#endif + if (fp->dsect != sect) { /* Fill sector buffer with file data */ + if (disk_read(fp->fs->drv, fp->buf, sect, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); + } +#endif + fp->dsect = sect; + } + rcnt = SS(fp->fs) - (fp->fptr % SS(fp->fs)); /* Get partial sector data from sector buffer */ + if (rcnt > btr) rcnt = btr; +#if _FS_TINY + if (move_window(fp->fs, fp->dsect)) /* Move sector window */ + ABORT(fp->fs, FR_DISK_ERR); + mem_cpy(rbuff, &fp->fs->win[fp->fptr % SS(fp->fs)], rcnt); /* Pick partial sector */ +#else + mem_cpy(rbuff, &fp->buf[fp->fptr % SS(fp->fs)], rcnt); /* Pick partial sector */ +#endif + } + + LEAVE_FF(fp->fs, FR_OK); +} + + + + +#if !_FS_READONLY +/*-----------------------------------------------------------------------*/ +/* Write File */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_write ( + FIL *fp, /* Pointer to the file object */ + const void *buff, /* Pointer to the data to be written */ + UINT btw, /* Number of bytes to write */ + UINT *bw /* Pointer to number of bytes written */ +) +{ + FRESULT res; + DWORD clst, sect; + UINT wcnt, cc; + const BYTE *wbuff = buff; + BYTE csect; + + + *bw = 0; /* Initialize byte counter */ + + res = validate(fp->fs, fp->id); /* Check validity of the object */ + if (res != FR_OK) LEAVE_FF(fp->fs, res); + if (fp->flag & FA__ERROR) /* Check abort flag */ + LEAVE_FF(fp->fs, FR_INT_ERR); + if (!(fp->flag & FA_WRITE)) /* Check access mode */ + LEAVE_FF(fp->fs, FR_DENIED); + if (fp->fsize + btw < fp->fsize) btw = 0; /* File size cannot reach 4GB */ + + for ( ; btw; /* Repeat until all data transferred */ + wbuff += wcnt, fp->fptr += wcnt, *bw += wcnt, btw -= wcnt) { + if ((fp->fptr % SS(fp->fs)) == 0) { /* On the sector boundary? */ + csect = (BYTE)(fp->fptr / SS(fp->fs) & (fp->fs->csize - 1)); /* Sector offset in the cluster */ + if (!csect) { /* On the cluster boundary? */ + if (fp->fptr == 0) { /* On the top of the file? */ + clst = fp->org_clust; /* Follow from the origin */ + if (clst == 0) /* When there is no cluster chain, */ + fp->org_clust = clst = create_chain(fp->fs, 0); /* Create a new cluster chain */ + } else { /* Middle or end of the file */ + clst = create_chain(fp->fs, fp->curr_clust); /* Follow or stretch cluster chain */ + } + if (clst == 0) break; /* Could not allocate a new cluster (disk full) */ + if (clst == 1) ABORT(fp->fs, FR_INT_ERR); + if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR); + fp->curr_clust = clst; /* Update current cluster */ + } +#if _FS_TINY + if (fp->fs->winsect == fp->dsect && move_window(fp->fs, 0)) /* Write back data buffer prior to following direct transfer */ + ABORT(fp->fs, FR_DISK_ERR); +#else + if (fp->flag & FA__DIRTY) { /* Write back data buffer prior to following direct transfer */ + if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); + fp->flag &= ~FA__DIRTY; + } +#endif + sect = clust2sect(fp->fs, fp->curr_clust); /* Get current sector */ + if (!sect) ABORT(fp->fs, FR_INT_ERR); + sect += csect; + cc = btw / SS(fp->fs); /* When remaining bytes >= sector size, */ + if (cc) { /* Write maximum contiguous sectors directly */ + if (csect + cc > fp->fs->csize) /* Clip at cluster boundary */ + cc = fp->fs->csize - csect; + if (disk_write(fp->fs->drv, wbuff, sect, (BYTE)cc) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); +#if _FS_TINY + if (fp->fs->winsect - sect < cc) { /* Refill sector cache if it gets dirty by the direct write */ + mem_cpy(fp->fs->win, wbuff + ((fp->fs->winsect - sect) * SS(fp->fs)), SS(fp->fs)); + fp->fs->wflag = 0; + } +#else + if (fp->dsect - sect < cc) { /* Refill sector cache if it gets dirty by the direct write */ + mem_cpy(fp->buf, wbuff + ((fp->dsect - sect) * SS(fp->fs)), SS(fp->fs)); + fp->flag &= ~FA__DIRTY; + } +#endif + wcnt = SS(fp->fs) * cc; /* Number of bytes transferred */ + continue; + } +#if _FS_TINY + if (fp->fptr >= fp->fsize) { /* Avoid silly buffer filling at growing edge */ + if (move_window(fp->fs, 0)) ABORT(fp->fs, FR_DISK_ERR); + fp->fs->winsect = sect; + } +#else + if (fp->dsect != sect) { /* Fill sector buffer with file data */ + if (fp->fptr < fp->fsize && + disk_read(fp->fs->drv, fp->buf, sect, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); + } +#endif + fp->dsect = sect; + } + wcnt = SS(fp->fs) - (fp->fptr % SS(fp->fs));/* Put partial sector into file I/O buffer */ + if (wcnt > btw) wcnt = btw; +#if _FS_TINY + if (move_window(fp->fs, fp->dsect)) /* Move sector window */ + ABORT(fp->fs, FR_DISK_ERR); + mem_cpy(&fp->fs->win[fp->fptr % SS(fp->fs)], wbuff, wcnt); /* Fit partial sector */ + fp->fs->wflag = 1; +#else + mem_cpy(&fp->buf[fp->fptr % SS(fp->fs)], wbuff, wcnt); /* Fit partial sector */ + fp->flag |= FA__DIRTY; +#endif + } + + if (fp->fptr > fp->fsize) fp->fsize = fp->fptr; /* Update file size if needed */ + fp->flag |= FA__WRITTEN; /* Set file change flag */ + + LEAVE_FF(fp->fs, FR_OK); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Synchronize the File Object */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_sync ( + FIL *fp /* Pointer to the file object */ +) +{ + FRESULT res; + DWORD tim; + BYTE *dir; + + + res = validate(fp->fs, fp->id); /* Check validity of the object */ + if (res == FR_OK) { + if (fp->flag & FA__WRITTEN) { /* Has the file been written? */ +#if !_FS_TINY /* Write-back dirty buffer */ + if (fp->flag & FA__DIRTY) { + if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK) + LEAVE_FF(fp->fs, FR_DISK_ERR); + fp->flag &= ~FA__DIRTY; + } +#endif + /* Update the directory entry */ + res = move_window(fp->fs, fp->dir_sect); + if (res == FR_OK) { + dir = fp->dir_ptr; + dir[DIR_Attr] |= AM_ARC; /* Set archive bit */ + ST_DWORD(dir+DIR_FileSize, fp->fsize); /* Update file size */ + ST_CLUST(dir, fp->org_clust); /* Update start cluster */ + tim = get_fattime(); /* Update updated time */ + ST_DWORD(dir+DIR_WrtTime, tim); + fp->flag &= ~FA__WRITTEN; + fp->fs->wflag = 1; + res = sync(fp->fs); + } + } + } + + LEAVE_FF(fp->fs, res); +} + +#endif /* !_FS_READONLY */ + + + + +/*-----------------------------------------------------------------------*/ +/* Close File */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_close ( + FIL *fp /* Pointer to the file object to be closed */ +) +{ + FRESULT res; + +#if _FS_READONLY + FATFS *fs = fp->fs; + res = validate(fs, fp->id); + if (res == FR_OK) fp->fs = 0; /* Discard file object */ + LEAVE_FF(fs, res); + +#else + res = f_sync(fp); /* Flush cached data */ +#if _FS_SHARE + if (res == FR_OK) { /* Decrement open counter */ +#if _FS_REENTRANT + res = validate(fp->fs, fp->id); + if (res == FR_OK) { + res = dec_lock(fp->lockid); + unlock_fs(fp->fs, FR_OK); + } +#else + res = dec_lock(fp->lockid); +#endif + } +#endif + if (res == FR_OK) fp->fs = 0; /* Discard file object */ + return res; +#endif +} + + + + +/*-----------------------------------------------------------------------*/ +/* Current Drive/Directory Handlings */ +/*-----------------------------------------------------------------------*/ + +#if _FS_RPATH >= 1 + +FRESULT f_chdrive ( + BYTE drv /* Drive number */ +) +{ + if (drv >= _VOLUMES) return FR_INVALID_DRIVE; + + CurrVol = drv; + + return FR_OK; +} + + + +FRESULT f_chdir ( + const TCHAR *path /* Pointer to the directory path */ +) +{ + FRESULT res; + DIR dj; + DEF_NAMEBUF; + + + res = chk_mounted(&path, &dj.fs, 0); + if (res == FR_OK) { + INIT_BUF(dj); + res = follow_path(&dj, path); /* Follow the path */ + FREE_BUF(); + if (res == FR_OK) { /* Follow completed */ + if (!dj.dir) { + dj.fs->cdir = dj.sclust; /* Start directory itself */ + } else { + if (dj.dir[DIR_Attr] & AM_DIR) /* Reached to the directory */ + dj.fs->cdir = LD_CLUST(dj.dir); + else + res = FR_NO_PATH; /* Reached but a file */ + } + } + if (res == FR_NO_FILE) res = FR_NO_PATH; + } + + LEAVE_FF(dj.fs, res); +} + + +#if _FS_RPATH >= 2 +FRESULT f_getcwd ( + TCHAR *path, /* Pointer to the directory path */ + UINT sz_path /* Size of path */ +) +{ + FRESULT res; + DIR dj; + UINT i, n; + DWORD ccl; + TCHAR *tp; + FILINFO fno; + DEF_NAMEBUF; + + + *path = 0; + res = chk_mounted((const TCHAR**)&path, &dj.fs, 0); /* Get current volume */ + if (res == FR_OK) { + INIT_BUF(dj); + i = sz_path; /* Bottom of buffer (dir stack base) */ + dj.sclust = dj.fs->cdir; /* Start to follow upper dir from current dir */ + while ((ccl = dj.sclust) != 0) { /* Repeat while current dir is a sub-dir */ + res = dir_sdi(&dj, 1); /* Get parent dir */ + if (res != FR_OK) break; + res = dir_read(&dj); + if (res != FR_OK) break; + dj.sclust = LD_CLUST(dj.dir); /* Goto parent dir */ + res = dir_sdi(&dj, 0); + if (res != FR_OK) break; + do { /* Find the entry links to the child dir */ + res = dir_read(&dj); + if (res != FR_OK) break; + if (ccl == LD_CLUST(dj.dir)) break; /* Found the entry */ + res = dir_next(&dj, 0); + } while (res == FR_OK); + if (res == FR_NO_FILE) res = FR_INT_ERR;/* It cannot be 'not found'. */ + if (res != FR_OK) break; +#if _USE_LFN + fno.lfname = path; + fno.lfsize = i; +#endif + get_fileinfo(&dj, &fno); /* Get the dir name and push it to the buffer */ + tp = fno.fname; + if (_USE_LFN && *path) tp = path; + for (n = 0; tp[n]; n++) ; + if (i < n + 3) { + res = FR_NOT_ENOUGH_CORE; break; + } + while (n) path[--i] = tp[--n]; + path[--i] = '/'; + } + tp = path; + if (res == FR_OK) { + *tp++ = '0' + CurrVol; /* Put drive number */ + *tp++ = ':'; + if (i == sz_path) { /* Root-dir */ + *tp++ = '/'; + } else { /* Sub-dir */ + do /* Add stacked path str */ + *tp++ = path[i++]; + while (i < sz_path); + } + } + *tp = 0; + FREE_BUF(); + } + + LEAVE_FF(dj.fs, res); +} +#endif /* _FS_RPATH >= 2 */ +#endif /* _FS_RPATH >= 1 */ + + + +#if _FS_MINIMIZE <= 2 +/*-----------------------------------------------------------------------*/ +/* Seek File R/W Pointer */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_lseek ( + FIL *fp, /* Pointer to the file object */ + DWORD ofs /* File pointer from top of file */ +) +{ + FRESULT res; + + + res = validate(fp->fs, fp->id); /* Check validity of the object */ + if (res != FR_OK) LEAVE_FF(fp->fs, res); + if (fp->flag & FA__ERROR) /* Check abort flag */ + LEAVE_FF(fp->fs, FR_INT_ERR); + +#if _USE_FASTSEEK + if (fp->cltbl) { /* Fast seek */ + DWORD cl, pcl, ncl, tcl, dsc, tlen, *tbl = fp->cltbl; + BYTE csc; + + tlen = *tbl++; + if (ofs == CREATE_LINKMAP) { /* Create link map table */ + cl = fp->org_clust; + if (cl) { + do { + if (tlen < 4) { /* Not enough table items */ + res = FR_NOT_ENOUGH_CORE; break; + } + tcl = cl; ncl = 0; + do { /* Get a fragment and store the top and length */ + pcl = cl; ncl++; + cl = get_fat(fp->fs, cl); + if (cl <= 1) ABORT(fp->fs, FR_INT_ERR); + if (cl == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR); + } while (cl == pcl + 1); + *tbl++ = ncl; *tbl++ = tcl; + tlen -= 2; + } while (cl < fp->fs->n_fatent); + } + *tbl = 0; /* Terminate table */ + + } else { /* Fast seek */ + if (ofs > fp->fsize) /* Clip offset at the file size */ + ofs = fp->fsize; + fp->fptr = ofs; /* Set file pointer */ + if (ofs) { + dsc = (ofs - 1) / SS(fp->fs); + cl = dsc / fp->fs->csize; + for (;;) { + ncl = *tbl++; + if (!ncl) ABORT(fp->fs, FR_INT_ERR); + if (cl < ncl) break; + cl -= ncl; tbl++; + } + fp->curr_clust = cl + *tbl; + csc = (BYTE)(dsc & (fp->fs->csize - 1)); + dsc = clust2sect(fp->fs, fp->curr_clust); + if (!dsc) ABORT(fp->fs, FR_INT_ERR); + dsc += csc; + if (fp->fptr % SS(fp->fs) && dsc != fp->dsect) { +#if !_FS_TINY +#if !_FS_READONLY + if (fp->flag & FA__DIRTY) { /* Flush dirty buffer if needed */ + if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); + fp->flag &= ~FA__DIRTY; + } +#endif + if (disk_read(fp->fs->drv, fp->buf, dsc, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); +#endif + fp->dsect = dsc; + } + } + } + } else +#endif + + /* Normal Seek */ + { + DWORD clst, bcs, nsect, ifptr; + + if (ofs > fp->fsize /* In read-only mode, clip offset with the file size */ +#if !_FS_READONLY + && !(fp->flag & FA_WRITE) +#endif + ) ofs = fp->fsize; + + ifptr = fp->fptr; + fp->fptr = nsect = 0; + if (ofs) { + bcs = (DWORD)fp->fs->csize * SS(fp->fs); /* Cluster size (byte) */ + if (ifptr > 0 && + (ofs - 1) / bcs >= (ifptr - 1) / bcs) { /* When seek to same or following cluster, */ + fp->fptr = (ifptr - 1) & ~(bcs - 1); /* start from the current cluster */ + ofs -= fp->fptr; + clst = fp->curr_clust; + } else { /* When seek to back cluster, */ + clst = fp->org_clust; /* start from the first cluster */ +#if !_FS_READONLY + if (clst == 0) { /* If no cluster chain, create a new chain */ + clst = create_chain(fp->fs, 0); + if (clst == 1) ABORT(fp->fs, FR_INT_ERR); + if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR); + fp->org_clust = clst; + } +#endif + fp->curr_clust = clst; + } + if (clst != 0) { + while (ofs > bcs) { /* Cluster following loop */ +#if !_FS_READONLY + if (fp->flag & FA_WRITE) { /* Check if in write mode or not */ + clst = create_chain(fp->fs, clst); /* Force stretch if in write mode */ + if (clst == 0) { /* When disk gets full, clip file size */ + ofs = bcs; break; + } + } else +#endif + clst = get_fat(fp->fs, clst); /* Follow cluster chain if not in write mode */ + if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR); + if (clst <= 1 || clst >= fp->fs->n_fatent) ABORT(fp->fs, FR_INT_ERR); + fp->curr_clust = clst; + fp->fptr += bcs; + ofs -= bcs; + } + fp->fptr += ofs; + if (ofs % SS(fp->fs)) { + nsect = clust2sect(fp->fs, clst); /* Current sector */ + if (!nsect) ABORT(fp->fs, FR_INT_ERR); + nsect += ofs / SS(fp->fs); + } + } + } + if (fp->fptr % SS(fp->fs) && nsect != fp->dsect) { +#if !_FS_TINY +#if !_FS_READONLY + if (fp->flag & FA__DIRTY) { /* Flush dirty buffer if needed */ + if (disk_write(fp->fs->drv, fp->buf, fp->dsect, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); + fp->flag &= ~FA__DIRTY; + } +#endif + if (disk_read(fp->fs->drv, fp->buf, nsect, 1) != RES_OK) + ABORT(fp->fs, FR_DISK_ERR); +#endif + fp->dsect = nsect; + } +#if !_FS_READONLY + if (fp->fptr > fp->fsize) { /* Set change flag if the file size is extended */ + fp->fsize = fp->fptr; + fp->flag |= FA__WRITTEN; + } +#endif + } + + LEAVE_FF(fp->fs, res); +} + + + +#if _FS_MINIMIZE <= 1 +/*-----------------------------------------------------------------------*/ +/* Create a Directroy Object */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_opendir ( + DIR *dj, /* Pointer to directory object to create */ + const TCHAR *path /* Pointer to the directory path */ +) +{ + FRESULT res; + DEF_NAMEBUF; + + res = chk_mounted(&path, &dj->fs, 0); + if (res == FR_OK) { + INIT_BUF(*dj); + res = follow_path(dj, path); /* Follow the path to the directory */ + FREE_BUF(); + if (res == FR_OK) { /* Follow completed */ + if (dj->dir) { /* It is not the root dir */ + if (dj->dir[DIR_Attr] & AM_DIR) { /* The object is a directory */ + dj->sclust = LD_CLUST(dj->dir); + } else { /* The object is not a directory */ + res = FR_NO_PATH; + } + } + if (res == FR_OK) { + dj->id = dj->fs->id; + res = dir_sdi(dj, 0); /* Rewind dir */ + } + } + if (res == FR_NO_FILE) res = FR_NO_PATH; + } + + LEAVE_FF(dj->fs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Read Directory Entry in Sequense */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_readdir ( + DIR *dj, /* Pointer to the open directory object */ + FILINFO *fno /* Pointer to file information to return */ +) +{ + FRESULT res; + DEF_NAMEBUF; + + + res = validate(dj->fs, dj->id); /* Check validity of the object */ + if (res == FR_OK) { + if (!fno) { + res = dir_sdi(dj, 0); /* Rewind the directory object */ + } else { + INIT_BUF(*dj); + res = dir_read(dj); /* Read an directory item */ + if (res == FR_NO_FILE) { /* Reached end of dir */ + dj->sect = 0; + res = FR_OK; + } + if (res == FR_OK) { /* A valid entry is found */ + get_fileinfo(dj, fno); /* Get the object information */ + res = dir_next(dj, 0); /* Increment index for next */ + if (res == FR_NO_FILE) { + dj->sect = 0; + res = FR_OK; + } + } + FREE_BUF(); + } + } + + LEAVE_FF(dj->fs, res); +} + + + +#if _FS_MINIMIZE == 0 +/*-----------------------------------------------------------------------*/ +/* Get File Status */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_stat ( + const TCHAR *path, /* Pointer to the file path */ + FILINFO *fno /* Pointer to file information to return */ +) +{ + FRESULT res; + DIR dj; + DEF_NAMEBUF; + + + res = chk_mounted(&path, &dj.fs, 0); + if (res == FR_OK) { + INIT_BUF(dj); + res = follow_path(&dj, path); /* Follow the file path */ + if (res == FR_OK) { /* Follow completed */ + if (dj.dir) /* Found an object */ + get_fileinfo(&dj, fno); + else /* It is root dir */ + res = FR_INVALID_NAME; + } + FREE_BUF(); + } + + LEAVE_FF(dj.fs, res); +} + + + +#if !_FS_READONLY +/*-----------------------------------------------------------------------*/ +/* Get Number of Free Clusters */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_getfree ( + const TCHAR *path, /* Pointer to the logical drive number (root dir) */ + DWORD *nclst, /* Pointer to the variable to return number of free clusters */ + FATFS **fatfs /* Pointer to pointer to corresponding file system object to return */ +) +{ + FRESULT res; + DWORD n, clst, sect, stat; + UINT i; + BYTE fat, *p; + + + /* Get drive number */ + res = chk_mounted(&path, fatfs, 0); + if (res == FR_OK) { + /* If free_clust is valid, return it without full cluster scan */ + if ((*fatfs)->free_clust <= (*fatfs)->n_fatent - 2) { + *nclst = (*fatfs)->free_clust; + } else { + /* Get number of free clusters */ + fat = (*fatfs)->fs_type; + n = 0; + if (fat == FS_FAT12) { + clst = 2; + do { + stat = get_fat(*fatfs, clst); + if (stat == 0xFFFFFFFF) { res = FR_DISK_ERR; break; } + if (stat == 1) { res = FR_INT_ERR; break; } + if (stat == 0) n++; + } while (++clst < (*fatfs)->n_fatent); + } else { + clst = (*fatfs)->n_fatent; + sect = (*fatfs)->fatbase; + i = 0; p = 0; + do { + if (!i) { + res = move_window(*fatfs, sect++); + if (res != FR_OK) break; + p = (*fatfs)->win; + i = SS(*fatfs); + } + if (fat == FS_FAT16) { + if (LD_WORD(p) == 0) n++; + p += 2; i -= 2; + } else { + if ((LD_DWORD(p) & 0x0FFFFFFF) == 0) n++; + p += 4; i -= 4; + } + } while (--clst); + } + (*fatfs)->free_clust = n; + if (fat == FS_FAT32) (*fatfs)->fsi_flag = 1; + *nclst = n; + } + } + LEAVE_FF(*fatfs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Truncate File */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_truncate ( + FIL *fp /* Pointer to the file object */ +) +{ + FRESULT res; + DWORD ncl; + + + res = validate(fp->fs, fp->id); /* Check validity of the object */ + if (res == FR_OK) { + if (fp->flag & FA__ERROR) { /* Check abort flag */ + res = FR_INT_ERR; + } else { + if (!(fp->flag & FA_WRITE)) /* Check access mode */ + res = FR_DENIED; + } + } + if (res == FR_OK) { + if (fp->fsize > fp->fptr) { + fp->fsize = fp->fptr; /* Set file size to current R/W point */ + fp->flag |= FA__WRITTEN; + if (fp->fptr == 0) { /* When set file size to zero, remove entire cluster chain */ + res = remove_chain(fp->fs, fp->org_clust); + fp->org_clust = 0; + } else { /* When truncate a part of the file, remove remaining clusters */ + ncl = get_fat(fp->fs, fp->curr_clust); + res = FR_OK; + if (ncl == 0xFFFFFFFF) res = FR_DISK_ERR; + if (ncl == 1) res = FR_INT_ERR; + if (res == FR_OK && ncl < fp->fs->n_fatent) { + res = put_fat(fp->fs, fp->curr_clust, 0x0FFFFFFF); + if (res == FR_OK) res = remove_chain(fp->fs, ncl); + } + } + } + if (res != FR_OK) fp->flag |= FA__ERROR; + } + + LEAVE_FF(fp->fs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Delete a File or Directory */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_unlink ( + const TCHAR *path /* Pointer to the file or directory path */ +) +{ + FRESULT res; + DIR dj, sdj; + BYTE *dir; + DWORD dclst; + DEF_NAMEBUF; + + + res = chk_mounted(&path, &dj.fs, 1); + if (res == FR_OK) { + INIT_BUF(dj); + res = follow_path(&dj, path); /* Follow the file path */ + if (_FS_RPATH && res == FR_OK && (dj.fn[NS] & NS_DOT)) + res = FR_INVALID_NAME; /* Cannot remove dot entry */ +#if _FS_SHARE + if (res == FR_OK) res = chk_lock(&dj, 2); /* Cannot remove open file */ +#endif + if (res == FR_OK) { /* The object is accessible */ + dir = dj.dir; + if (!dir) { + res = FR_INVALID_NAME; /* Cannot remove the start directory */ + } else { + if (dir[DIR_Attr] & AM_RDO) + res = FR_DENIED; /* Cannot remove R/O object */ + } + dclst = LD_CLUST(dir); + if (res == FR_OK && (dir[DIR_Attr] & AM_DIR)) { /* Is it a sub-dir? */ + if (dclst < 2) { + res = FR_INT_ERR; + } else { + mem_cpy(&sdj, &dj, sizeof(DIR)); /* Check if the sub-dir is empty or not */ + sdj.sclust = dclst; + res = dir_sdi(&sdj, 2); /* Exclude dot entries */ + if (res == FR_OK) { + res = dir_read(&sdj); + if (res == FR_OK /* Not empty dir */ +#if _FS_RPATH + || dclst == sdj.fs->cdir /* Current dir */ +#endif + ) res = FR_DENIED; + if (res == FR_NO_FILE) res = FR_OK; /* Empty */ + } + } + } + if (res == FR_OK) { + res = dir_remove(&dj); /* Remove the directory entry */ + if (res == FR_OK) { + if (dclst) /* Remove the cluster chain if exist */ + res = remove_chain(dj.fs, dclst); + if (res == FR_OK) res = sync(dj.fs); + } + } + } + FREE_BUF(); + } + LEAVE_FF(dj.fs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Create a Directory */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_mkdir ( + const TCHAR *path /* Pointer to the directory path */ +) +{ + FRESULT res; + DIR dj; + BYTE *dir, n; + DWORD dsc, dcl, pcl, tim = get_fattime(); + DEF_NAMEBUF; + + + res = chk_mounted(&path, &dj.fs, 1); + if (res == FR_OK) { + INIT_BUF(dj); + res = follow_path(&dj, path); /* Follow the file path */ + if (res == FR_OK) res = FR_EXIST; /* Any object with same name is already existing */ + if (_FS_RPATH && res == FR_NO_FILE && (dj.fn[NS] & NS_DOT)) + res = FR_INVALID_NAME; + if (res == FR_NO_FILE) { /* Can create a new directory */ + dcl = create_chain(dj.fs, 0); /* Allocate a cluster for the new directory table */ + res = FR_OK; + if (dcl == 0) res = FR_DENIED; /* No space to allocate a new cluster */ + if (dcl == 1) res = FR_INT_ERR; + if (dcl == 0xFFFFFFFF) res = FR_DISK_ERR; + if (res == FR_OK) /* Flush FAT */ + res = move_window(dj.fs, 0); + if (res == FR_OK) { /* Initialize the new directory table */ + dsc = clust2sect(dj.fs, dcl); + dir = dj.fs->win; + mem_set(dir, 0, SS(dj.fs)); + mem_set(dir+DIR_Name, ' ', 8+3); /* Create "." entry */ + dir[DIR_Name] = '.'; + dir[DIR_Attr] = AM_DIR; + ST_DWORD(dir+DIR_WrtTime, tim); + ST_CLUST(dir, dcl); + mem_cpy(dir+32, dir, 32); /* Create ".." entry */ + dir[33] = '.'; pcl = dj.sclust; + if (dj.fs->fs_type == FS_FAT32 && pcl == dj.fs->dirbase) + pcl = 0; + ST_CLUST(dir+32, pcl); + for (n = dj.fs->csize; n; n--) { /* Write dot entries and clear following sectors */ + dj.fs->winsect = dsc++; + dj.fs->wflag = 1; + res = move_window(dj.fs, 0); + if (res != FR_OK) break; + mem_set(dir, 0, SS(dj.fs)); + } + } + if (res == FR_OK) res = dir_register(&dj); /* Register the object to the directoy */ + if (res != FR_OK) { + remove_chain(dj.fs, dcl); /* Could not register, remove cluster chain */ + } else { + dir = dj.dir; + dir[DIR_Attr] = AM_DIR; /* Attribute */ + ST_DWORD(dir+DIR_WrtTime, tim); /* Created time */ + ST_CLUST(dir, dcl); /* Table start cluster */ + dj.fs->wflag = 1; + res = sync(dj.fs); + } + } + FREE_BUF(); + } + + LEAVE_FF(dj.fs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Change Attribute */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_chmod ( + const TCHAR *path, /* Pointer to the file path */ + BYTE value, /* Attribute bits */ + BYTE mask /* Attribute mask to change */ +) +{ + FRESULT res; + DIR dj; + BYTE *dir; + DEF_NAMEBUF; + + + res = chk_mounted(&path, &dj.fs, 1); + if (res == FR_OK) { + INIT_BUF(dj); + res = follow_path(&dj, path); /* Follow the file path */ + FREE_BUF(); + if (_FS_RPATH && res == FR_OK && (dj.fn[NS] & NS_DOT)) + res = FR_INVALID_NAME; + if (res == FR_OK) { + dir = dj.dir; + if (!dir) { /* Is it a root directory? */ + res = FR_INVALID_NAME; + } else { /* File or sub directory */ + mask &= AM_RDO|AM_HID|AM_SYS|AM_ARC; /* Valid attribute mask */ + dir[DIR_Attr] = (value & mask) | (dir[DIR_Attr] & (BYTE)~mask); /* Apply attribute change */ + dj.fs->wflag = 1; + res = sync(dj.fs); + } + } + } + + LEAVE_FF(dj.fs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Change Timestamp */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_utime ( + const TCHAR *path, /* Pointer to the file/directory name */ + const FILINFO *fno /* Pointer to the time stamp to be set */ +) +{ + FRESULT res; + DIR dj; + BYTE *dir; + DEF_NAMEBUF; + + + res = chk_mounted(&path, &dj.fs, 1); + if (res == FR_OK) { + INIT_BUF(dj); + res = follow_path(&dj, path); /* Follow the file path */ + FREE_BUF(); + if (_FS_RPATH && res == FR_OK && (dj.fn[NS] & NS_DOT)) + res = FR_INVALID_NAME; + if (res == FR_OK) { + dir = dj.dir; + if (!dir) { /* Root directory */ + res = FR_INVALID_NAME; + } else { /* File or sub-directory */ + ST_WORD(dir+DIR_WrtTime, fno->ftime); + ST_WORD(dir+DIR_WrtDate, fno->fdate); + dj.fs->wflag = 1; + res = sync(dj.fs); + } + } + } + + LEAVE_FF(dj.fs, res); +} + + + + +/*-----------------------------------------------------------------------*/ +/* Rename File/Directory */ +/*-----------------------------------------------------------------------*/ + +FRESULT f_rename ( + const TCHAR *path_old, /* Pointer to the old name */ + const TCHAR *path_new /* Pointer to the new name */ +) +{ + FRESULT res; + DIR djo, djn; + BYTE buf[21], *dir; + DWORD dw; + DEF_NAMEBUF; + + + res = chk_mounted(&path_old, &djo.fs, 1); + if (res == FR_OK) { + djn.fs = djo.fs; + INIT_BUF(djo); + res = follow_path(&djo, path_old); /* Check old object */ + if (_FS_RPATH && res == FR_OK && (djo.fn[NS] & NS_DOT)) + res = FR_INVALID_NAME; +#if _FS_SHARE + if (res == FR_OK) res = chk_lock(&djo, 2); +#endif + if (res == FR_OK) { /* Old object is found */ + if (!djo.dir) { /* Is root dir? */ + res = FR_NO_FILE; + } else { + mem_cpy(buf, djo.dir+DIR_Attr, 21); /* Save the object information except for name */ + mem_cpy(&djn, &djo, sizeof(DIR)); /* Check new object */ + res = follow_path(&djn, path_new); + if (res == FR_OK) res = FR_EXIST; /* The new object name is already existing */ + if (res == FR_NO_FILE) { /* Is it a valid path and no name collision? */ +/* Start critical section that any interruption or error can cause cross-link */ + res = dir_register(&djn); /* Register the new entry */ + if (res == FR_OK) { + dir = djn.dir; /* Copy object information except for name */ + mem_cpy(dir+13, buf+2, 19); + dir[DIR_Attr] = buf[0] | AM_ARC; + djo.fs->wflag = 1; + if (djo.sclust != djn.sclust && (dir[DIR_Attr] & AM_DIR)) { /* Update .. entry in the directory if needed */ + dw = clust2sect(djn.fs, LD_CLUST(dir)); + if (!dw) { + res = FR_INT_ERR; + } else { + res = move_window(djn.fs, dw); + dir = djn.fs->win+32; /* .. entry */ + if (res == FR_OK && dir[1] == '.') { + dw = (djn.fs->fs_type == FS_FAT32 && djn.sclust == djn.fs->dirbase) ? 0 : djn.sclust; + ST_CLUST(dir, dw); + djn.fs->wflag = 1; + } + } + } + if (res == FR_OK) { + res = dir_remove(&djo); /* Remove old entry */ + if (res == FR_OK) + res = sync(djo.fs); + } + } +/* End critical section */ + } + } + } + FREE_BUF(); + } + LEAVE_FF(djo.fs, res); +} + +#endif /* !_FS_READONLY */ +#endif /* _FS_MINIMIZE == 0 */ +#endif /* _FS_MINIMIZE <= 1 */ +#endif /* _FS_MINIMIZE <= 2 */ + + + +/*-----------------------------------------------------------------------*/ +/* Forward data to the stream directly (available on only tiny cfg) */ +/*-----------------------------------------------------------------------*/ +#if _USE_FORWARD && _FS_TINY + +FRESULT f_forward ( + FIL *fp, /* Pointer to the file object */ + UINT (*func)(const BYTE*,UINT), /* Pointer to the streaming function */ + UINT btr, /* Number of bytes to forward */ + UINT *bf /* Pointer to number of bytes forwarded */ +) +{ + FRESULT res; + DWORD remain, clst, sect; + UINT rcnt; + BYTE csect; + + + *bf = 0; /* Initialize byte counter */ + + res = validate(fp->fs, fp->id); /* Check validity of the object */ + if (res != FR_OK) LEAVE_FF(fp->fs, res); + if (fp->flag & FA__ERROR) /* Check error flag */ + LEAVE_FF(fp->fs, FR_INT_ERR); + if (!(fp->flag & FA_READ)) /* Check access mode */ + LEAVE_FF(fp->fs, FR_DENIED); + + remain = fp->fsize - fp->fptr; + if (btr > remain) btr = (UINT)remain; /* Truncate btr by remaining bytes */ + + for ( ; btr && (*func)(0, 0); /* Repeat until all data transferred or stream becomes busy */ + fp->fptr += rcnt, *bf += rcnt, btr -= rcnt) { + csect = (BYTE)(fp->fptr / SS(fp->fs) & (fp->fs->csize - 1)); /* Sector offset in the cluster */ + if ((fp->fptr % SS(fp->fs)) == 0) { /* On the sector boundary? */ + if (!csect) { /* On the cluster boundary? */ + clst = (fp->fptr == 0) ? /* On the top of the file? */ + fp->org_clust : get_fat(fp->fs, fp->curr_clust); + if (clst <= 1) ABORT(fp->fs, FR_INT_ERR); + if (clst == 0xFFFFFFFF) ABORT(fp->fs, FR_DISK_ERR); + fp->curr_clust = clst; /* Update current cluster */ + } + } + sect = clust2sect(fp->fs, fp->curr_clust); /* Get current data sector */ + if (!sect) ABORT(fp->fs, FR_INT_ERR); + sect += csect; + if (move_window(fp->fs, sect)) /* Move sector window */ + ABORT(fp->fs, FR_DISK_ERR); + fp->dsect = sect; + rcnt = SS(fp->fs) - (WORD)(fp->fptr % SS(fp->fs)); /* Forward data from sector window */ + if (rcnt > btr) rcnt = btr; + rcnt = (*func)(&fp->fs->win[(WORD)fp->fptr % SS(fp->fs)], rcnt); + if (!rcnt) ABORT(fp->fs, FR_INT_ERR); + } + + LEAVE_FF(fp->fs, FR_OK); +} +#endif /* _USE_FORWARD */ + + + +#if _USE_MKFS && !_FS_READONLY +/*-----------------------------------------------------------------------*/ +/* Create File System on the Drive */ +/*-----------------------------------------------------------------------*/ +#define N_ROOTDIR 512 /* Multiple of 32 */ +#define N_FATS 1 /* 1 or 2 */ + + +FRESULT f_mkfs ( + BYTE drv, /* Logical drive number */ + BYTE sfd, /* Partitioning rule 0:FDISK, 1:SFD */ + UINT au /* Allocation unit size [bytes] */ +) +{ + static const WORD vst[] = { 1024, 512, 256, 128, 64, 32, 16, 8, 4, 2, 0}; + static const WORD cst[] = {32768, 16384, 8192, 4096, 2048, 16384, 8192, 4096, 2048, 1024, 512}; + BYTE fmt, md, *tbl; + DWORD n_clst, vs, n, wsect; + UINT i; + DWORD b_vol, b_fat, b_dir, b_data; /* Offset (LBA) */ + DWORD n_vol, n_rsv, n_fat, n_dir; /* Size */ + FATFS *fs; + DSTATUS stat; + + /* Check mounted drive and clear work area */ + if (drv >= _VOLUMES) return FR_INVALID_DRIVE; + fs = FatFs[drv]; + if (!fs) return FR_NOT_ENABLED; + fs->fs_type = 0; + drv = LD2PD(drv); + + /* Get disk statics */ + stat = disk_initialize(drv); + if (stat & STA_NOINIT) return FR_NOT_READY; + if (stat & STA_PROTECT) return FR_WRITE_PROTECTED; +#if _MAX_SS != 512 /* Get disk sector size */ + if (disk_ioctl(drv, GET_SECTOR_SIZE, &SS(fs)) != RES_OK) + return FR_DISK_ERR; +#endif + if (disk_ioctl(drv, GET_SECTOR_COUNT, &n_vol) != RES_OK || n_vol < 128) + return FR_DISK_ERR; + b_vol = (sfd) ? 0 : 63; /* Volume start sector */ + n_vol -= b_vol; + if (au & (au - 1)) au = 0; /* Check validity of the allocation unit size */ + if (!au) { /* AU auto selection */ + vs = n_vol / (2000 / (SS(fs) / 512)); + for (i = 0; vs < vst[i]; i++) ; + au = cst[i]; + } + au /= SS(fs); /* Number of sectors per cluster */ + if (au == 0) au = 1; + if (au > 128) au = 128; + + /* Pre-compute number of clusters and FAT syb-type */ + n_clst = n_vol / au; + fmt = FS_FAT12; + if (n_clst >= MIN_FAT16) fmt = FS_FAT16; + if (n_clst >= MIN_FAT32) fmt = FS_FAT32; + + /* Determine offset and size of FAT structure */ + if (fmt == FS_FAT32) { + n_fat = ((n_clst * 4) + 8 + SS(fs) - 1) / SS(fs); + n_rsv = 32; + n_dir = 0; + } else { + n_fat = (fmt == FS_FAT12) ? (n_clst * 3 + 1) / 2 + 3 : (n_clst * 2) + 4; + n_fat = (n_fat + SS(fs) - 1) / SS(fs); + n_rsv = 1; + n_dir = N_ROOTDIR * 32UL / SS(fs); + } + b_fat = b_vol + n_rsv; /* FAT area start sector */ + b_dir = b_fat + n_fat * N_FATS; /* Directory area start sector */ + b_data = b_dir + n_dir; /* Data area start sector */ + if (n_vol < b_data + au) return FR_MKFS_ABORTED; /* Too small volume */ + + /* Align data start sector to erase block boundary (for flash memory media) */ + if (disk_ioctl(drv, GET_BLOCK_SIZE, &n) != RES_OK || !n || n > 32768) n = 1; + n = (b_data + n - 1) & ~(n - 1); /* Next nearest erase block from current data start */ + n = (n - b_data) / N_FATS; + if (fmt == FS_FAT32) { /* FAT32: Move FAT offset */ + n_rsv += n; + b_fat += n; + } else { /* FAT12/16: Expand FAT size */ + n_fat += n; + } + + /* Determine number of cluster and final check of validity of the FAT sub-type */ + n_clst = (n_vol - n_rsv - n_fat * N_FATS - n_dir) / au; + if ( (fmt == FS_FAT16 && n_clst < MIN_FAT16) + || (fmt == FS_FAT32 && n_clst < MIN_FAT32)) + return FR_MKFS_ABORTED; + + /* Create partition table if required */ + if (sfd) { + md = 0xF0; + } else { + DWORD n_disk = b_vol + n_vol; + + mem_set(fs->win, 0, SS(fs)); + tbl = fs->win+MBR_Table; + ST_DWORD(tbl, 0x00010180); /* Partition start in CHS */ + if (n_disk < 63UL * 255 * 1024) { /* Partition end in CHS */ + n_disk = n_disk / 63 / 255; + tbl[7] = (BYTE)n_disk; + tbl[6] = (BYTE)((n_disk >> 2) | 63); + } else { + ST_WORD(&tbl[6], 0xFFFF); + } + tbl[5] = 254; + if (fmt != FS_FAT32) /* System ID */ + tbl[4] = (n_vol < 0x10000) ? 0x04 : 0x06; + else + tbl[4] = 0x0c; + ST_DWORD(tbl+8, 63); /* Partition start in LBA */ + ST_DWORD(tbl+12, n_vol); /* Partition size in LBA */ + ST_WORD(tbl+64, 0xAA55); /* Signature */ + if (disk_write(drv, fs->win, 0, 1) != RES_OK) + return FR_DISK_ERR; + md = 0xF8; + } + + /* Create volume boot record */ + tbl = fs->win; /* Clear sector */ + mem_set(tbl, 0, SS(fs)); + mem_cpy(tbl, "\xEB\xFE\x90" "MSDOS5.0", 11);/* Boot code, OEM name */ + i = SS(fs); /* Sector size */ + ST_WORD(tbl+BPB_BytsPerSec, i); + tbl[BPB_SecPerClus] = (BYTE)au; /* Sectors per cluster */ + ST_WORD(tbl+BPB_RsvdSecCnt, n_rsv); /* Reserved sectors */ + tbl[BPB_NumFATs] = N_FATS; /* Number of FATs */ + i = (fmt == FS_FAT32) ? 0 : N_ROOTDIR; /* Number of rootdir entries */ + ST_WORD(tbl+BPB_RootEntCnt, i); + if (n_vol < 0x10000) { /* Number of total sectors */ + ST_WORD(tbl+BPB_TotSec16, n_vol); + } else { + ST_DWORD(tbl+BPB_TotSec32, n_vol); + } + tbl[BPB_Media] = md; /* Media descriptor */ + ST_WORD(tbl+BPB_SecPerTrk, 63); /* Number of sectors per track */ + ST_WORD(tbl+BPB_NumHeads, 255); /* Number of heads */ + ST_DWORD(tbl+BPB_HiddSec, b_vol); /* Hidden sectors */ + n = get_fattime(); /* Use current time as VSN */ + if (fmt == FS_FAT32) { + ST_DWORD(tbl+BS_VolID32, n); /* VSN */ + ST_DWORD(tbl+BPB_FATSz32, n_fat); /* Number of sectors per FAT */ + ST_DWORD(tbl+BPB_RootClus, 2); /* Root directory start cluster (2) */ + ST_WORD(tbl+BPB_FSInfo, 1); /* FSInfo record offset (VBR+1) */ + ST_WORD(tbl+BPB_BkBootSec, 6); /* Backup boot record offset (VBR+6) */ + tbl[BS_DrvNum32] = 0x80; /* Drive number */ + tbl[BS_BootSig32] = 0x29; /* Extended boot signature */ + mem_cpy(tbl+BS_VolLab32, "NO NAME " "FAT32 ", 19); /* Volume label, FAT signature */ + } else { + ST_DWORD(tbl+BS_VolID, n); /* VSN */ + ST_WORD(tbl+BPB_FATSz16, n_fat); /* Number of sectors per FAT */ + tbl[BS_DrvNum] = 0x80; /* Drive number */ + tbl[BS_BootSig] = 0x29; /* Extended boot signature */ + mem_cpy(tbl+BS_VolLab, "NO NAME " "FAT ", 19); /* Volume label, FAT signature */ + } + ST_WORD(tbl+BS_55AA, 0xAA55); /* Signature (Offset is fixed here regardless of sector size) */ + if (disk_write(drv, tbl, b_vol, 1) != RES_OK)/* Write original (VBR) */ + return FR_DISK_ERR; + if (fmt == FS_FAT32) /* Write backup (VBR+6) */ + disk_write(drv, tbl, b_vol + 6, 1); + + /* Initialize FAT area */ + wsect = b_fat; + for (i = 0; i < N_FATS; i++) { + mem_set(tbl, 0, SS(fs)); /* 1st sector of the FAT */ + n = md; /* Media descriptor byte */ + if (fmt != FS_FAT32) { + n |= (fmt == FS_FAT12) ? 0x00FFFF00 : 0xFFFFFF00; + ST_DWORD(tbl+0, n); /* Reserve cluster #0-1 (FAT12/16) */ + } else { + n |= 0xFFFFFF00; + ST_DWORD(tbl+0, n); /* Reserve cluster #0-1 (FAT32) */ + ST_DWORD(tbl+4, 0xFFFFFFFF); + ST_DWORD(tbl+8, 0x0FFFFFFF); /* Reserve cluster #2 for root dir */ + } + if (disk_write(drv, tbl, wsect++, 1) != RES_OK) + return FR_DISK_ERR; + mem_set(tbl, 0, SS(fs)); /* Fill following FAT entries with zero */ + for (n = 1; n < n_fat; n++) { /* This loop may take a time on FAT32 volume due to many single sector write */ + if (disk_write(drv, tbl, wsect++, 1) != RES_OK) + return FR_DISK_ERR; + } + } + + /* Initialize root directory */ + i = (fmt == FS_FAT32) ? au : n_dir; + do { + if (disk_write(drv, tbl, wsect++, 1) != RES_OK) + return FR_DISK_ERR; + } while (--i); + +#if _USE_ERASE /* Erase data area if needed */ + { + DWORD eb[2]; + + eb[0] = wsect; eb[1] = wsect + n_clst * au - 1; + disk_ioctl(drv, CTRL_ERASE_SECTOR, eb); + } +#endif + + /* Create FSInfo if needed */ + if (fmt == FS_FAT32) { + ST_WORD(tbl+BS_55AA, 0xAA55); + ST_DWORD(tbl+FSI_LeadSig, 0x41615252); + ST_DWORD(tbl+FSI_StrucSig, 0x61417272); + ST_DWORD(tbl+FSI_Free_Count, n_clst - 1); + ST_DWORD(tbl+FSI_Nxt_Free, 0xFFFFFFFF); + disk_write(drv, tbl, b_vol + 1, 1); /* Write original (VBR+1) */ + disk_write(drv, tbl, b_vol + 7, 1); /* Write backup (VBR+7) */ + } + + return (disk_ioctl(drv, CTRL_SYNC, (void*)0) == RES_OK) ? FR_OK : FR_DISK_ERR; +} + +#endif /* _USE_MKFS && !_FS_READONLY */ + + + + +#if _USE_STRFUNC +/*-----------------------------------------------------------------------*/ +/* Get a string from the file */ +/*-----------------------------------------------------------------------*/ +TCHAR* f_gets ( + TCHAR* buff, /* Pointer to the string buffer to read */ + int len, /* Size of string buffer (characters) */ + FIL* fil /* Pointer to the file object */ +) +{ + int n = 0; + TCHAR c, *p = buff; + BYTE s[2]; + UINT rc; + + + while (n < len - 1) { /* Read bytes until buffer gets filled */ + f_read(fil, s, 1, &rc); + if (rc != 1) break; /* Break on EOF or error */ + c = s[0]; +#if _LFN_UNICODE /* Read a character in UTF-8 encoding */ + if (c >= 0x80) { + if (c < 0xC0) continue; /* Skip stray trailer */ + if (c < 0xE0) { /* Two-byte sequense */ + f_read(fil, s, 1, &rc); + if (rc != 1) break; + c = ((c & 0x1F) << 6) | (s[0] & 0x3F); + if (c < 0x80) c = '?'; + } else { + if (c < 0xF0) { /* Three-byte sequense */ + f_read(fil, s, 2, &rc); + if (rc != 2) break; + c = (c << 12) | ((s[0] & 0x3F) << 6) | (s[1] & 0x3F); + if (c < 0x800) c = '?'; + } else { /* Reject four-byte sequense */ + c = '?'; + } + } + } +#endif +#if _USE_STRFUNC >= 2 + if (c == '\r') continue; /* Strip '\r' */ +#endif + *p++ = c; + n++; + if (c == '\n') break; /* Break on EOL */ + } + *p = 0; + return n ? buff : 0; /* When no data read (eof or error), return with error. */ +} + + + +#if !_FS_READONLY +#include <stdarg.h> +/*-----------------------------------------------------------------------*/ +/* Put a character to the file */ +/*-----------------------------------------------------------------------*/ +int f_putc ( + TCHAR c, /* A character to be output */ + FIL* fil /* Pointer to the file object */ +) +{ + UINT bw, btw; + BYTE s[3]; + + +#if _USE_STRFUNC >= 2 + if (c == '\n') f_putc ('\r', fil); /* LF -> CRLF conversion */ +#endif + +#if _LFN_UNICODE /* Write the character in UTF-8 encoding */ + if (c < 0x80) { /* 7-bit */ + s[0] = (BYTE)c; + btw = 1; + } else { + if (c < 0x800) { /* 11-bit */ + s[0] = (BYTE)(0xC0 | (c >> 6)); + s[1] = (BYTE)(0x80 | (c & 0x3F)); + btw = 2; + } else { /* 16-bit */ + s[0] = (BYTE)(0xE0 | (c >> 12)); + s[1] = (BYTE)(0x80 | ((c >> 6) & 0x3F)); + s[2] = (BYTE)(0x80 | (c & 0x3F)); + btw = 3; + } + } +#else /* Write the character without conversion */ + s[0] = (BYTE)c; + btw = 1; +#endif + f_write(fil, s, btw, &bw); /* Write the char to the file */ + return (bw == btw) ? 1 : EOF; /* Return the result */ +} + + + + +/*-----------------------------------------------------------------------*/ +/* Put a string to the file */ +/*-----------------------------------------------------------------------*/ +int f_puts ( + const TCHAR* str, /* Pointer to the string to be output */ + FIL* fil /* Pointer to the file object */ +) +{ + int n; + + + for (n = 0; *str; str++, n++) { + if (f_putc(*str, fil) == EOF) return EOF; + } + return n; +} + + + + +/*-----------------------------------------------------------------------*/ +/* Put a formatted string to the file */ +/*-----------------------------------------------------------------------*/ +int f_printf ( + FIL* fil, /* Pointer to the file object */ + const TCHAR* str, /* Pointer to the format string */ + ... /* Optional arguments... */ +) +{ + va_list arp; + BYTE f, r; + UINT i, w; + ULONG val; + TCHAR c, d, s[16]; + int res, cc; + + + va_start(arp, str); + + for (cc = res = 0; cc != EOF; res += cc) { + c = *str++; + if (c == 0) break; /* End of string */ + if (c != '%') { /* Non escape character */ + cc = f_putc(c, fil); + if (cc != EOF) cc = 1; + continue; + } + w = f = 0; + c = *str++; + if (c == '0') { /* Flag: '0' padding */ + f = 1; c = *str++; + } + while (IsDigit(c)) { /* Precision */ + w = w * 10 + c - '0'; + c = *str++; + } + if (c == 'l' || c == 'L') { /* Prefix: Size is long int */ + f |= 2; c = *str++; + } + if (!c) break; + d = c; + if (IsLower(d)) d -= 0x20; + switch (d) { /* Type is... */ + case 'S' : /* String */ + cc = f_puts(va_arg(arp, TCHAR*), fil); continue; + case 'C' : /* Character */ + cc = f_putc((TCHAR)va_arg(arp, int), fil); continue; + case 'B' : /* Binary */ + r = 2; break; + case 'O' : /* Octal */ + r = 8; break; + case 'D' : /* Signed decimal */ + case 'U' : /* Unsigned decimal */ + r = 10; break; + case 'X' : /* Hexdecimal */ + r = 16; break; + default: /* Unknown */ + cc = f_putc(c, fil); continue; + } + + /* Get an argument */ + val = (f & 2) ? va_arg(arp, long) : ((d == 'D') ? (long)va_arg(arp, int) : va_arg(arp, unsigned int)); + if (d == 'D' && (val & 0x80000000)) { + val = 0 - val; + f |= 4; + } + /* Put it in numeral string */ + i = 0; + do { + d = (TCHAR)(val % r); val /= r; + if (d > 9) { + d += 7; + if (c == 'x') d += 0x20; + } + s[i++] = d + '0'; + } while (val && i < sizeof(s) / sizeof(s[0])); + if (f & 4) s[i++] = '-'; + cc = 0; + while (i < w-- && cc != EOF) { + cc = f_putc((TCHAR)((f & 1) ? '0' : ' '), fil); + res++; + } + do { + cc = f_putc(s[--i], fil); + res++; + } while (i && cc != EOF); + if (cc != EOF) cc = 0; + } + + va_end(arp); + return (cc == EOF) ? cc : res; +} + +#endif /* !_FS_READONLY */ +#endif /* _USE_STRFUNC */ + +#endif /* XPAR_PS7_SD_0_S_AXI_BASEADDR */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ff.h b/quad/xsdk_workspace/zybo_fsbl/src/ff.h new file mode 100644 index 0000000000000000000000000000000000000000..a2cf4907a0c1fb7e207492ca4c8b68fb14e5b821 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/ff.h @@ -0,0 +1,541 @@ +/*---------------------------------------------------------------------------/ +/ FatFs - FAT file system module include file R0.08a (C)ChaN, 2010 +/----------------------------------------------------------------------------/ +/ FatFs module is a generic FAT file system module for small embedded systems. +/ This is a free software that opened for education, research and commercial +/ developments under license policy of following trems. +/ +/ Copyright (C) 2010, ChaN, all right reserved. +/ +/ * The FatFs module is a free software and there is NO WARRANTY. +/ * No restriction on use. You can use, modify and redistribute it for +/ personal, non-profit or commercial product UNDER YOUR RESPONSIBILITY. +/ * Redistributions of source code must retain the above copyright notice. +/ +/----------------------------------------------------------------------------*/ + +#ifndef _FATFS +#define _FATFS 8255 /* Revision ID */ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "integer.h" /* Basic integer types */ +#include "ffconf.h" /* FatFs configuration options */ + +#if _FATFS != _FFCONF +#error Wrong configuration file (ffconf.h). +#endif + + +/* DBCS code ranges and SBCS extend char conversion table */ + +#if _CODE_PAGE == 932 /* Japanese Shift-JIS */ +#define _DF1S 0x81 /* DBC 1st byte range 1 start */ +#define _DF1E 0x9F /* DBC 1st byte range 1 end */ +#define _DF2S 0xE0 /* DBC 1st byte range 2 start */ +#define _DF2E 0xFC /* DBC 1st byte range 2 end */ +#define _DS1S 0x40 /* DBC 2nd byte range 1 start */ +#define _DS1E 0x7E /* DBC 2nd byte range 1 end */ +#define _DS2S 0x80 /* DBC 2nd byte range 2 start */ +#define _DS2E 0xFC /* DBC 2nd byte range 2 end */ + +#elif _CODE_PAGE == 936 /* Simplified Chinese GBK */ +#define _DF1S 0x81 +#define _DF1E 0xFE +#define _DS1S 0x40 +#define _DS1E 0x7E +#define _DS2S 0x80 +#define _DS2E 0xFE + +#elif _CODE_PAGE == 949 /* Korean */ +#define _DF1S 0x81 +#define _DF1E 0xFE +#define _DS1S 0x41 +#define _DS1E 0x5A +#define _DS2S 0x61 +#define _DS2E 0x7A +#define _DS3S 0x81 +#define _DS3E 0xFE + +#elif _CODE_PAGE == 950 /* Traditional Chinese Big5 */ +#define _DF1S 0x81 +#define _DF1E 0xFE +#define _DS1S 0x40 +#define _DS1E 0x7E +#define _DS2S 0xA1 +#define _DS2E 0xFE + +#elif _CODE_PAGE == 437 /* U.S. (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x9A,0x90,0x41,0x8E,0x41,0x8F,0x80,0x45,0x45,0x45,0x49,0x49,0x49,0x8E,0x8F,0x90,0x92,0x92,0x4F,0x99,0x4F,0x55,0x55,0x59,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 720 /* Arabic (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x45,0x41,0x84,0x41,0x86,0x43,0x45,0x45,0x45,0x49,0x49,0x8D,0x8E,0x8F,0x90,0x92,0x92,0x93,0x94,0x95,0x49,0x49,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 737 /* Greek (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x92,0x92,0x93,0x94,0x95,0x96,0x97,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87, \ + 0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0xAA,0x92,0x93,0x94,0x95,0x96,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0x97,0xEA,0xEB,0xEC,0xE4,0xED,0xEE,0xE7,0xE8,0xF1,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 775 /* Baltic (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x9A,0x91,0xA0,0x8E,0x95,0x8F,0x80,0xAD,0xED,0x8A,0x8A,0xA1,0x8D,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0x95,0x96,0x97,0x97,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \ + 0xA0,0xA1,0xE0,0xA3,0xA3,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xB5,0xB6,0xB7,0xB8,0xBD,0xBE,0xC6,0xC7,0xA5,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE3,0xE8,0xE8,0xEA,0xEA,0xEE,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 850 /* Multilingual Latin 1 (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xB7,0x8F,0x80,0xD2,0xD3,0xD4,0xD8,0xD7,0xDE,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0xE3,0xEA,0xEB,0x59,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \ + 0xB5,0xD6,0xE0,0xE9,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE7,0xE7,0xE9,0xEA,0xEB,0xED,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 852 /* Latin 2 (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xDE,0x8F,0x80,0x9D,0xD3,0x8A,0x8A,0xD7,0x8D,0x8E,0x8F,0x90,0x91,0x91,0xE2,0x99,0x95,0x95,0x97,0x97,0x99,0x9A,0x9B,0x9B,0x9D,0x9E,0x9F, \ + 0xB5,0xD6,0xE0,0xE9,0xA4,0xA4,0xA6,0xA6,0xA8,0xA8,0xAA,0x8D,0xAC,0xB8,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBD,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC6,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD1,0xD1,0xD2,0xD3,0xD2,0xD5,0xD6,0xD7,0xB7,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE3,0xD5,0xE6,0xE6,0xE8,0xE9,0xE8,0xEB,0xED,0xED,0xDD,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xEB,0xFC,0xFC,0xFE,0xFF} + +#elif _CODE_PAGE == 855 /* Cyrillic (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x81,0x81,0x83,0x83,0x85,0x85,0x87,0x87,0x89,0x89,0x8B,0x8B,0x8D,0x8D,0x8F,0x8F,0x91,0x91,0x93,0x93,0x95,0x95,0x97,0x97,0x99,0x99,0x9B,0x9B,0x9D,0x9D,0x9F,0x9F, \ + 0xA1,0xA1,0xA3,0xA3,0xA5,0xA5,0xA7,0xA7,0xA9,0xA9,0xAB,0xAB,0xAD,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB6,0xB6,0xB8,0xB8,0xB9,0xBA,0xBB,0xBC,0xBE,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD1,0xD1,0xD3,0xD3,0xD5,0xD5,0xD7,0xD7,0xDD,0xD9,0xDA,0xDB,0xDC,0xDD,0xE0,0xDF, \ + 0xE0,0xE2,0xE2,0xE4,0xE4,0xE6,0xE6,0xE8,0xE8,0xEA,0xEA,0xEC,0xEC,0xEE,0xEE,0xEF,0xF0,0xF2,0xF2,0xF4,0xF4,0xF6,0xF6,0xF8,0xF8,0xFA,0xFA,0xFC,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 857 /* Turkish (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xB7,0x8F,0x80,0xD2,0xD3,0xD4,0xD8,0xD7,0x98,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0xE3,0xEA,0xEB,0x98,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9E, \ + 0xB5,0xD6,0xE0,0xE9,0xA5,0xA5,0xA6,0xA6,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xDE,0x59,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 858 /* Multilingual Latin 1 + Euro (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xB7,0x8F,0x80,0xD2,0xD3,0xD4,0xD8,0xD7,0xDE,0x8E,0x8F,0x90,0x92,0x92,0xE2,0x99,0xE3,0xEA,0xEB,0x59,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \ + 0xB5,0xD6,0xE0,0xE9,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD1,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE7,0xE7,0xE9,0xEA,0xEB,0xED,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 862 /* Hebrew (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0x21,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 866 /* Russian (OEM) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0x90,0x91,0x92,0x93,0x9d,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F,0xF0,0xF0,0xF2,0xF2,0xF4,0xF4,0xF6,0xF6,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 874 /* Thai (OEM, Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 1250 /* Central Europe (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x8A,0x9B,0x8C,0x8D,0x8E,0x8F, \ + 0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xA3,0xB4,0xB5,0xB6,0xB7,0xB8,0xA5,0xAA,0xBB,0xBC,0xBD,0xBC,0xAF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xFF} + +#elif _CODE_PAGE == 1251 /* Cyrillic (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x82,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x80,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x8A,0x9B,0x8C,0x8D,0x8E,0x8F, \ + 0xA0,0xA2,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB2,0xA5,0xB5,0xB6,0xB7,0xA8,0xB9,0xAA,0xBB,0xA3,0xBD,0xBD,0xAF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF} + +#elif _CODE_PAGE == 1252 /* Latin 1 (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0xAd,0x9B,0x8C,0x9D,0xAE,0x9F, \ + 0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0x9F} + +#elif _CODE_PAGE == 1253 /* Greek (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xA2,0xB8,0xB9,0xBA, \ + 0xE0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xF2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xFB,0xBC,0xFD,0xBF,0xFF} + +#elif _CODE_PAGE == 1254 /* Turkish (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x8A,0x9B,0x8C,0x9D,0x9E,0x9F, \ + 0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0x9F} + +#elif _CODE_PAGE == 1255 /* Hebrew (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF,0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 1256 /* Arabic (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x8C,0x9D,0x9E,0x9F, \ + 0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0x41,0xE1,0x41,0xE3,0xE4,0xE5,0xE6,0x43,0x45,0x45,0x45,0x45,0xEC,0xED,0x49,0x49,0xF0,0xF1,0xF2,0xF3,0x4F,0xF5,0xF6,0xF7,0xF8,0x55,0xFA,0x55,0x55,0xFD,0xFE,0xFF} + +#elif _CODE_PAGE == 1257 /* Baltic (Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \ + 0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xA8,0xB9,0xAA,0xBB,0xBC,0xBD,0xBE,0xAF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xFF} + +#elif _CODE_PAGE == 1258 /* Vietnam (OEM, Windows) */ +#define _DF1S 0 +#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0xAC,0x9D,0x9E,0x9F, \ + 0xA0,0x21,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF,0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF,0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \ + 0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xEC,0xCD,0xCE,0xCF,0xD0,0xD1,0xF2,0xD3,0xD4,0xD5,0xD6,0xF7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xFE,0x9F} + +#elif _CODE_PAGE == 1 /* ASCII (for only non-LFN cfg) */ +#define _DF1S 0 + +#else +#error Unknown code page + +#endif + + + +/* Definitions of volume management */ + +#if _MULTI_PARTITION /* Multiple partition configuration */ +#define LD2PD(vol) (VolToPart[vol].pd) /* Get physical drive# */ +#define LD2PT(vol) (VolToPart[vol].pt) /* Get partition# */ +typedef struct { + BYTE pd; /* Physical drive# */ + BYTE pt; /* Partition # (0-3) */ +} PARTITION; +extern const PARTITION VolToPart[]; /* Volume - Physical location resolution table */ + +#else /* Single partition configuration */ +#define LD2PD(vol) (vol) /* Logical drive# is bound to the same physical drive# */ +#define LD2PT(vol) 0 /* Always mounts the 1st partition */ + +#endif + + + +/* Type of path name strings on FatFs API */ + +#if _LFN_UNICODE /* Unicode string */ +#if !_USE_LFN +#error _LFN_UNICODE must be 0 in non-LFN cfg. +#endif +#ifndef _INC_TCHAR +typedef WCHAR TCHAR; +#define _T(x) L ## x +#define _TEXT(x) L ## x +#endif + +#else /* ANSI/OEM string */ +#ifndef _INC_TCHAR +typedef char TCHAR; +#define _T(x) x +#define _TEXT(x) x +#endif + +#endif + + + +/* File system object structure (FATFS) */ + +typedef struct { + BYTE fs_type; /* FAT sub-type (0:Not mounted) */ + BYTE drv; /* Physical drive number */ + BYTE csize; /* Sectors per cluster (1,2,4...128) */ + BYTE n_fats; /* Number of FAT copies (1,2) */ + BYTE wflag; /* win[] dirty flag (1:must be written back) */ + BYTE fsi_flag; /* fsinfo dirty flag (1:must be written back) */ + WORD id; /* File system mount ID */ + WORD n_rootdir; /* Number of root directory entries (FAT12/16) */ +#if _MAX_SS != 512 + WORD ssize; /* Bytes per sector (512,1024,2048,4096) */ +#endif +#if _FS_REENTRANT + _SYNC_t sobj; /* Identifier of sync object */ +#endif +#if !_FS_READONLY + DWORD last_clust; /* Last allocated cluster */ + DWORD free_clust; /* Number of free clusters */ + DWORD fsi_sector; /* fsinfo sector (FAT32) */ +#endif +#if _FS_RPATH + DWORD cdir; /* Current directory start cluster (0:root) */ +#endif + DWORD n_fatent; /* Number of FAT entries (= number of clusters + 2) */ + DWORD fsize; /* Sectors per FAT */ + DWORD fatbase; /* FAT start sector */ + DWORD dirbase; /* Root directory start sector (FAT32:Cluster#) */ + DWORD database; /* Data start sector */ + DWORD winsect; /* Current sector appearing in the win[] */ + BYTE win[_MAX_SS]; /* Disk access window for Directory, FAT (and Data on tiny cfg) */ +} FATFS; + + + +/* File object structure (FIL) */ + +typedef struct { + FATFS* fs; /* Pointer to the owner file system object */ + WORD id; /* Owner file system mount ID */ + BYTE flag; /* File status flags */ + BYTE pad1; + DWORD fptr; /* File read/write pointer (0 on file open) */ + DWORD fsize; /* File size */ + DWORD org_clust; /* File start cluster (0 when fsize==0) */ + DWORD curr_clust; /* Current cluster */ + DWORD dsect; /* Current data sector */ +#if !_FS_READONLY + DWORD dir_sect; /* Sector containing the directory entry */ + BYTE* dir_ptr; /* Ponter to the directory entry in the window */ +#endif +#if _USE_FASTSEEK + DWORD* cltbl; /* Pointer to the cluster link map table (null on file open) */ +#endif +#if _FS_SHARE + UINT lockid; /* File lock ID (index of file semaphore table) */ +#endif +#if !_FS_TINY + BYTE buf[_MAX_SS]; /* File data read/write buffer */ +#endif +} FIL; + + + +/* Directory object structure (DIR) */ + +typedef struct { + FATFS* fs; /* Pointer to the owner file system object */ + WORD id; /* Owner file system mount ID */ + WORD index; /* Current read/write index number */ + DWORD sclust; /* Table start cluster (0:Root dir) */ + DWORD clust; /* Current cluster */ + DWORD sect; /* Current sector */ + BYTE* dir; /* Pointer to the current SFN entry in the win[] */ + BYTE* fn; /* Pointer to the SFN (in/out) {file[8],ext[3],status[1]} */ +#if _USE_LFN + WCHAR* lfn; /* Pointer to the LFN working buffer */ + WORD lfn_idx; /* Last matched LFN index number (0xFFFF:No LFN) */ +#endif +} DIR; + + + +/* File status structure (FILINFO) */ + +typedef struct { + DWORD fsize; /* File size */ + WORD fdate; /* Last modified date */ + WORD ftime; /* Last modified time */ + BYTE fattrib; /* Attribute */ + TCHAR fname[13]; /* Short file name (8.3 format) */ +#if _USE_LFN + TCHAR* lfname; /* Pointer to the LFN buffer */ + UINT lfsize; /* Size of LFN buffer in TCHAR */ +#endif +} FILINFO; + + + +/* File function return code (FRESULT) */ + +typedef enum { + FR_OK = 0, /* (0) Succeeded */ + FR_DISK_ERR, /* (1) A hard error occured in the low level disk I/O layer */ + FR_INT_ERR, /* (2) Assertion failed */ + FR_NOT_READY, /* (3) The physical drive cannot work */ + FR_NO_FILE, /* (4) Could not find the file */ + FR_NO_PATH, /* (5) Could not find the path */ + FR_INVALID_NAME, /* (6) The path name format is invalid */ + FR_DENIED, /* (7) Acces denied due to prohibited access or directory full */ + FR_EXIST, /* (8) Acces denied due to prohibited access */ + FR_INVALID_OBJECT, /* (9) The file/directory object is invalid */ + FR_WRITE_PROTECTED, /* (10) The physical drive is write protected */ + FR_INVALID_DRIVE, /* (11) The logical drive number is invalid */ + FR_NOT_ENABLED, /* (12) The volume has no work area */ + FR_NO_FILESYSTEM, /* (13) There is no valid FAT volume on the physical drive */ + FR_MKFS_ABORTED, /* (14) The f_mkfs() aborted due to any parameter error */ + FR_TIMEOUT, /* (15) Could not get a grant to access the volume within defined period */ + FR_LOCKED, /* (16) The operation is rejected according to the file shareing policy */ + FR_NOT_ENOUGH_CORE, /* (17) LFN working buffer could not be allocated */ + FR_TOO_MANY_OPEN_FILES /* (18) Number of open files > _FS_SHARE */ +} FRESULT; + + + +/*--------------------------------------------------------------*/ +/* FatFs module application interface */ + +FRESULT f_mount (BYTE, FATFS*); /* Mount/Unmount a logical drive */ +FRESULT f_open (FIL*, const TCHAR*, BYTE); /* Open or create a file */ +FRESULT f_read (FIL*, void*, UINT, UINT*); /* Read data from a file */ +FRESULT f_lseek (FIL*, DWORD); /* Move file pointer of a file object */ +FRESULT f_close (FIL*); /* Close an open file object */ +FRESULT f_opendir (DIR*, const TCHAR*); /* Open an existing directory */ +FRESULT f_readdir (DIR*, FILINFO*); /* Read a directory item */ +FRESULT f_stat (const TCHAR*, FILINFO*); /* Get file status */ + +#if !_FS_READONLY +FRESULT f_write (FIL*, const void*, UINT, UINT*); /* Write data to a file */ +FRESULT f_getfree (const TCHAR*, DWORD*, FATFS**); /* Get number of free clusters on the drive */ +FRESULT f_truncate (FIL*); /* Truncate file */ +FRESULT f_sync (FIL*); /* Flush cached data of a writing file */ +FRESULT f_unlink (const TCHAR*); /* Delete an existing file or directory */ +FRESULT f_mkdir (const TCHAR*); /* Create a new directory */ +FRESULT f_chmod (const TCHAR*, BYTE, BYTE); /* Change attriburte of the file/dir */ +FRESULT f_utime (const TCHAR*, const FILINFO*); /* Change timestamp of the file/dir */ +FRESULT f_rename (const TCHAR*, const TCHAR*); /* Rename/Move a file or directory */ +#endif + +#if _USE_FORWARD +FRESULT f_forward (FIL*, UINT(*)(const BYTE*,UINT), UINT, UINT*); /* Forward data to the stream */ +#endif + +#if _USE_MKFS +FRESULT f_mkfs (BYTE, BYTE, UINT); /* Create a file system on the drive */ +#endif + +#if _FS_RPATH +FRESULT f_chdrive (BYTE); /* Change current drive */ +FRESULT f_chdir (const TCHAR*); /* Change current directory */ +FRESULT f_getcwd (TCHAR*, UINT); /* Get current directory */ +#endif + +#if _USE_STRFUNC +int f_putc (TCHAR, FIL*); /* Put a character to the file */ +int f_puts (const TCHAR*, FIL*); /* Put a string to the file */ +int f_printf (FIL*, const TCHAR*, ...); /* Put a formatted string to the file */ +TCHAR* f_gets (TCHAR*, int, FIL*); /* Get a string from the file */ +#ifndef EOF +#define EOF (-1) +#endif +#endif + +#define f_eof(fp) (((fp)->fptr == (fp)->fsize) ? 1 : 0) +#define f_error(fp) (((fp)->flag & FA__ERROR) ? 1 : 0) +#define f_tell(fp) ((fp)->fptr) +#define f_size(fp) ((fp)->fsize) + + + +/*--------------------------------------------------------------*/ +/* Additional user defined functions */ + +/* RTC function */ +#if !_FS_READONLY +DWORD get_fattime (void); +#endif + +/* Unicode support functions */ +#if _USE_LFN /* Unicode - OEM code conversion */ +WCHAR ff_convert (WCHAR, UINT); /* OEM-Unicode bidirectional conversion */ +WCHAR ff_wtoupper (WCHAR); /* Unicode upper-case conversion */ +#if _USE_LFN == 3 /* Memory functions */ +void* ff_memalloc (UINT); /* Allocate memory block */ +void ff_memfree (void*); /* Free memory block */ +#endif +#endif + +/* Sync functions */ +#if _FS_REENTRANT +int ff_cre_syncobj (BYTE, _SYNC_t*);/* Create a sync object */ +int ff_del_syncobj (_SYNC_t); /* Delete a sync object */ +int ff_req_grant (_SYNC_t); /* Lock sync object */ +void ff_rel_grant (_SYNC_t); /* Unlock sync object */ +#endif + + + + +/*--------------------------------------------------------------*/ +/* Flags and offset address */ + + +/* File access control and file status flags (FIL.flag) */ + +#define FA_READ 0x01 +#define FA_OPEN_EXISTING 0x00 +#define FA__ERROR 0x80 + +#if !_FS_READONLY +#define FA_WRITE 0x02 +#define FA_CREATE_NEW 0x04 +#define FA_CREATE_ALWAYS 0x08 +#define FA_OPEN_ALWAYS 0x10 +#define FA__WRITTEN 0x20 +#define FA__DIRTY 0x40 +#endif + + +/* FAT sub type (FATFS.fs_type) */ + +#define FS_FAT12 1 +#define FS_FAT16 2 +#define FS_FAT32 3 + + +/* File attribute bits for directory entry */ + +#define AM_RDO 0x01 /* Read only */ +#define AM_HID 0x02 /* Hidden */ +#define AM_SYS 0x04 /* System */ +#define AM_VOL 0x08 /* Volume label */ +#define AM_LFN 0x0F /* LFN entry */ +#define AM_DIR 0x10 /* Directory */ +#define AM_ARC 0x20 /* Archive */ +#define AM_MASK 0x3F /* Mask of defined bits */ + + +/* Fast seek function */ +#define CREATE_LINKMAP 0xFFFFFFFF + + +/*--------------------------------*/ +/* Multi-byte word access macros */ + +#if _WORD_ACCESS == 1 /* Enable word access to the FAT structure */ + #define LD_WORD(ptr) (WORD)(*(WORD*)(BYTE*)(ptr)) + #define LD_DWORD(ptr) (DWORD)(*(DWORD*)(BYTE*)(ptr)) + #define ST_WORD(ptr,val) *(WORD*)(BYTE*)(ptr)=(WORD)(val) + #define ST_DWORD(ptr,val) *(DWORD*)(BYTE*)(ptr)=(DWORD)(val) +#else /* Use byte-by-byte access to the FAT structure */ + #define LD_WORD(ptr) (WORD)(((WORD)*(BYTE*)((ptr)+1)<<8)|(WORD)*(BYTE*)(ptr)) + #define LD_DWORD(ptr) (DWORD)(((DWORD)*(BYTE*)((ptr)+3)<<24)|((DWORD)*(BYTE*)((ptr)+2)<<16)|((WORD)*(BYTE*)((ptr)+1)<<8)|*(BYTE*)(ptr)) + #define ST_WORD(ptr,val) *(BYTE*)(ptr)=(BYTE)(val); *(BYTE*)((ptr)+1)=(BYTE)((WORD)(val)>>8) + #define ST_DWORD(ptr,val) *(BYTE*)(ptr)=(BYTE)(val); *(BYTE*)((ptr)+1)=(BYTE)((WORD)(val)>>8); *(BYTE*)((ptr)+2)=(BYTE)((DWORD)(val)>>16); *(BYTE*)((ptr)+3)=(BYTE)((DWORD)(val)>>24) +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* _FATFS */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ffconf.h b/quad/xsdk_workspace/zybo_fsbl/src/ffconf.h new file mode 100644 index 0000000000000000000000000000000000000000..1b57f9705773169512413e4f60ba658703f12fd9 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/ffconf.h @@ -0,0 +1,188 @@ +/*---------------------------------------------------------------------------/ +/ FatFs - FAT file system module configuration file R0.08a (C)ChaN, 2010 +/----------------------------------------------------------------------------/ +/ +/ CAUTION! Do not forget to make clean the project after any changes to +/ the configuration options. +/ +/----------------------------------------------------------------------------*/ +#ifndef _FFCONF +#define _FFCONF 8255 /* Revision ID */ + + +/*---------------------------------------------------------------------------/ +/ Function and Buffer Configurations +/----------------------------------------------------------------------------*/ + +#define _FS_TINY 1 /* 0:Normal or 1:Tiny */ +/* When _FS_TINY is set to 1, FatFs uses the sector buffer in the file system +/ object instead of the sector buffer in the individual file object for file +/ data transfer. This reduces memory consumption 512 bytes each file object. */ + + +#define _FS_READONLY 1 /* 0:Read/Write or 1:Read only */ +/* Setting _FS_READONLY to 1 defines read only configuration. This removes +/ writing functions, f_write, f_sync, f_unlink, f_mkdir, f_chmod, f_rename, +/ f_truncate and useless f_getfree. */ + + +#define _FS_MINIMIZE 1 /* 0 to 3 */ +/* The _FS_MINIMIZE option defines minimization level to remove some functions. +/ +/ 0: Full function. +/ 1: f_stat, f_getfree, f_unlink, f_mkdir, f_chmod, f_truncate and f_rename +/ are removed. +/ 2: f_opendir and f_readdir are removed in addition to 1. +/ 3: f_lseek is removed in addition to 2. */ + + +#define _USE_STRFUNC 0 /* 0:Disable or 1/2:Enable */ +/* To enable string functions, set _USE_STRFUNC to 1 or 2. */ + + +#define _USE_MKFS 0 /* 0:Disable or 1:Enable */ +/* To enable f_mkfs function, set _USE_MKFS to 1 and set _FS_READONLY to 0 */ + + +#define _USE_FORWARD 0 /* 0:Disable or 1:Enable */ +/* To enable f_forward function, set _USE_FORWARD to 1 and set _FS_TINY to 1. */ + + +#define _USE_FASTSEEK 0 /* 0:Disable or 1:Enable */ +/* To enable fast seek feature, set _USE_FASTSEEK to 1. */ + + + +/*---------------------------------------------------------------------------/ +/ Locale and Namespace Configurations +/----------------------------------------------------------------------------*/ + +#define _CODE_PAGE 437 +/* The _CODE_PAGE specifies the OEM code page to be used on the target system. +/ Incorrect setting of the code page can cause a file open failure. +/ +/ 932 - Japanese Shift-JIS (DBCS, OEM, Windows) +/ 936 - Simplified Chinese GBK (DBCS, OEM, Windows) +/ 949 - Korean (DBCS, OEM, Windows) +/ 950 - Traditional Chinese Big5 (DBCS, OEM, Windows) +/ 1250 - Central Europe (Windows) +/ 1251 - Cyrillic (Windows) +/ 1252 - Latin 1 (Windows) +/ 1253 - Greek (Windows) +/ 1254 - Turkish (Windows) +/ 1255 - Hebrew (Windows) +/ 1256 - Arabic (Windows) +/ 1257 - Baltic (Windows) +/ 1258 - Vietnam (OEM, Windows) +/ 437 - U.S. (OEM) +/ 720 - Arabic (OEM) +/ 737 - Greek (OEM) +/ 775 - Baltic (OEM) +/ 850 - Multilingual Latin 1 (OEM) +/ 858 - Multilingual Latin 1 + Euro (OEM) +/ 852 - Latin 2 (OEM) +/ 855 - Cyrillic (OEM) +/ 866 - Russian (OEM) +/ 857 - Turkish (OEM) +/ 862 - Hebrew (OEM) +/ 874 - Thai (OEM, Windows) +/ 1 - ASCII only (Valid for non LFN cfg.) +*/ + + +#define _USE_LFN 0 /* 0 to 3 */ +#define _MAX_LFN 255 /* Maximum LFN length to handle (12 to 255) */ +/* The _USE_LFN option switches the LFN support. +/ +/ 0: Disable LFN feature. _MAX_LFN and _LFN_UNICODE have no effect. +/ 1: Enable LFN with static working buffer on the BSS. Always NOT reentrant. +/ 2: Enable LFN with dynamic working buffer on the STACK. +/ 3: Enable LFN with dynamic working buffer on the HEAP. +/ +/ The LFN working buffer occupies (_MAX_LFN + 1) * 2 bytes. To enable LFN, +/ Unicode handling functions ff_convert() and ff_wtoupper() must be added +/ to the project. When enable to use heap, memory control functions +/ ff_memalloc() and ff_memfree() must be added to the project. */ + + +#define _LFN_UNICODE 0 /* 0:ANSI/OEM or 1:Unicode */ +/* To switch the character code set on FatFs API to Unicode, +/ enable LFN feature and set _LFN_UNICODE to 1. */ + + +#define _FS_RPATH 0 /* 0 to 2 */ +/* The _FS_RPATH option configures relative path feature. +/ +/ 0: Disable relative path feature and remove related functions. +/ 1: Enable relative path. f_chdrive() and f_chdir() are available. +/ 2: f_getcwd() is available in addition to 1. +/ +/ Note that output of the f_readdir fnction is affected by this option. */ + + + +/*---------------------------------------------------------------------------/ +/ Physical Drive Configurations +/----------------------------------------------------------------------------*/ + +#define _VOLUMES 1 +/* Number of volumes (logical drives) to be used. */ + + +#define _MAX_SS 512 /* 512, 1024, 2048 or 4096 */ +/* Maximum sector size to be handled. +/ Always set 512 for memory card and hard disk but a larger value may be +/ required for floppy disk (512/1024) and optical disk (512/2048). +/ When _MAX_SS is larger than 512, GET_SECTOR_SIZE command must be implememted +/ to the disk_ioctl function. */ + + +#define _MULTI_PARTITION 0 /* 0:Single partition or 1:Multiple partition */ +/* When set to 0, each volume is bound to the same physical drive number and +/ it can mount only first primaly partition. When it is set to 1, each volume +/ is tied to the partitions listed in VolToPart[]. */ + + +#define _USE_ERASE 0 /* 0:Disable or 1:Enable */ +/* To enable sector erase feature, set _USE_ERASE to 1. */ + + + +/*---------------------------------------------------------------------------/ +/ System Configurations +/----------------------------------------------------------------------------*/ + +#define _WORD_ACCESS 0 /* 0 or 1 */ +/* Set 0 first and it is always compatible with all platforms. The _WORD_ACCESS +/ option defines which access method is used to the word data on the FAT volume. +/ +/ 0: Byte-by-byte access. +/ 1: Word access. Do not choose this unless following condition is met. +/ +/ When the byte order on the memory is big-endian or address miss-aligned word +/ access results incorrect behavior, the _WORD_ACCESS must be set to 0. +/ If it is not the case, the value can also be set to 1 to improve the +/ performance and code size. */ + + +/* Include a header file here to define sync object types on the O/S */ +/* #include <windows.h>, <ucos_ii.h.h>, <semphr.h> or ohters. */ + +#define _FS_REENTRANT 0 /* 0:Disable or 1:Enable */ +#define _FS_TIMEOUT 1000 /* Timeout period in unit of time ticks */ +#define _SYNC_t HANDLE /* O/S dependent type of sync object. e.g. HANDLE, OS_EVENT*, ID and etc.. */ + +/* The _FS_REENTRANT option switches the reentrancy of the FatFs module. +/ +/ 0: Disable reentrancy. _SYNC_t and _FS_TIMEOUT have no effect. +/ 1: Enable reentrancy. Also user provided synchronization handlers, +/ ff_req_grant, ff_rel_grant, ff_del_syncobj and ff_cre_syncobj +/ function must be added to the project. */ + + +#define _FS_SHARE 0 /* 0:Disable or >=1:Enable */ +/* To enable file shareing feature, set _FS_SHARE to 1 or greater. The value + defines how many files can be opened simultaneously. */ + + +#endif /* _FFCONFIG */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/fsbl.h b/quad/xsdk_workspace/zybo_fsbl/src/fsbl.h new file mode 100644 index 0000000000000000000000000000000000000000..edb0e039e48855ad119c479d2a66d84465a5f979 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/fsbl.h @@ -0,0 +1,477 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file fsbl.h +* +* Contains the function prototypes, defines and macros for the +* First Stage Boot Loader (FSBL) functionality +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a jz 03/04/11 Initial release +* 2.00a mb 06/06/12 Removed the qspi define, will be picked from +* xparameters.h file +* 3.00a np/mb 08/08/12 Added the error codes for the FSBL hook errors. +* Added the debug levels +* 4.00a sgd 02/28/13 Removed DDR initialization check +* Removed DDR ECC initialization code +* Modified hand off address check to 1MB +* Added RSA authentication support +* Removed LPBK_DLY_ADJ register setting code as we use +* divisor 8 +* Removed check for Fabric is already initialized +* +* CR's fixed and description +* 689026: FSBL doesn't hold PL resets active during +* bit download +* Resolution: PL resets are released just before +* handoff +* +* 689077: FSBL hangs at Handoff clearing the +* TX UART buffer +* Resolution: STDOUT_BASEADDRESS macro value changes +* based UART select, hence used STDOUT_BASEADDRESS +* as UART base address +* +* 695578: FSBL failed to load standalone application +* in secure bootmode +* Resolution: Application will be placed at load address +* instead of DDR temporary address +* +* 699475: FSBL functionality is broken and its +* not able to boot in QSPI/NAND bootmode +* Resolution: New flags are added DevCfg driver +* for handling loopback +* XDCFG_CONCURRENT_NONSEC_READ_WRITE +* XDCFG_CONCURRENT_SECURE_READ_WRITE +* +* 683145: Define stack area for FIQ, UNDEF modes +* in linker file +* Resolution: FSBL linker modified to create stack area +* for FIQ, UNDEF +* +* 705664: FSBL fails to decrypt the bitstream when +* the image is AES encrypted using non-zero key value +* Resolution: Fabric cleaning will not be done +* for AES-E-Fuse encryption +* +* Watchdog disabled for AES E-Fuse encryption +* +* 5.00a sgd 05/17/13 Fallback support for E-Fuse encryption +* Added QSPI Flash Size > 128Mbit support +* QSPI Dual Stack support +* Added Md5 checksum support +* +* CR's fixed and description +* 692045 FSBL: Linker script of FSBL has PHDR workaround, +* this needs to be fixed +* Resolution: Removed PHDR from Linker file +* +* 704287 FSBL: fsbl.h file has a few error codes that +* are not used by FSBL, that needs to be removed +* Resolution: Removed unused error codes +* +* 704379 FSBL: Check if DDR is in proper state before +* handoff +* Resolution: Added DDR initialization check +* +* 709077 If FSBL_DEBUG and FSBL_DEBUG_INFO are defined, +* the debug level is FSBL_DEBUG only. +* +* 710128 FSBL: Linux boot failing without load attribute +* set for Linux partitions in BIF +* Resolution: FSBL will load partitions with valid load +* address and stop loading if any invalid load address +* +* 708728 Issues seen while making HP interconnect +* 32 bit wide +* Resolution: ps7_post_config function generated by PCW +* will be called after Bit stream download +* Added MMC support +* 6.00a kc 07/31/2013 CR's fixed and description +* 724166 FSBL doesn’t use PPK authenticated by Boot ROM +* for authenticating the Partition images +* Resolution: FSBL now uses the PPK left by Boot ROM in +* OCM for authencating the SPK +* +* 724165 Partition Header used by FSBL is not +* authenticated +* Resolution: FSBL now authenticates the partition header +* +* 691150 ps7_init does not check for peripheral +* initialization failures or timeout on polls +* Resolution: Return value of ps7_init() is now checked +* by FSBL and prints the error string +* +* 708316 PS7_init.tcl file should have Error mechanism +* for all mask_poll +* Resolution: Return value of ps7_init() is now checked +* by FSBL and prints the error string +* +* 732062 FSBL fails to build if UART not available +* Resolution: Added define to call xil_printf only +* if uart is defined +* +* 722979 Provide customer-friendly changelogs in FSBL +* Resolution: Added CR description for all the files +* +* 732865 Backward compatibility for ps7_init function +* Resolution: Added a new define for ps7_init success +* and value is defined based on ps7_init define +* +* Fix for CR#739711 - FSBL not able to read Large +* QSPI (512M) in IO Mode +* Resolution: Modified the address calculation +* algorithm in dual parallel mode for QSPI +* +* </pre> +* +* </pre> +* +* @note +* +* Flags in FSBL +* +* FSBL_PERF +* +* This Flag can be set at compilation time. This flag is set for +* measuring the performance of FSBL.That is the time taken to execute is +* measured.when this flag is set.Execution time with reference to +* global timer is taken here +* +* Total Execution time is the time taken for executing FSBL till handoff +* to any application . +* If there is a bitstream in the partition header then the +* execution time includes the copying of the bitstream to DDR +* (in case of SD/NAND bootmode) +* and programming the devcfg dma is accounted. +* +* FSBL provides two debug levels +* DEBUG GENERAL - fsbl_printf under this category will appear only when the +* FSBL_DEBUG flag is set during compilation +* DEBUG_INFO - fsbl_printf under this category will appear when the +* FSBL_DEBUG_INFO flag is set during compilation +* For a more detailed output log can be used. +* FSBL_DEBUG_RSA - Define this macro to print more detailed values used in +* RSA functions +* These macros are input to the fsbl_printf function +* +* DEBUG LEVELS +* FSBL_DEBUG level is level 1, when this flag is set all the fsbl_prints +* that are with the DEBUG_GENERAL argument are shown +* FSBL_DEBUG_INFO is level 2, when this flag is set during the +* compilation , the fsbl_printf with DEBUG_INFO will appear on the com port +* +* DEFAULT LEVEL +* By default no print messages will appear. +* +* NON_PS_INSTANTIATED_BITSTREAM +* +* FSBL will not enable the level shifters for a NON PS instantiated +* Bitstream.This flag can be set during compilation for a NON PS instantiated +* bitstream +* +* ECC_ENABLE +* This flag will be defined in the ps7_init.h file when ECC is enabled +* in the DDR configuration (XPS GUI) +* +* RSA_SUPPORT +* This flag is used to enable authentication feature +* Default this macro disabled, reason to avoid increase in code size +* +* MMC_SUPPORT +* This flag is used to enable MMC support feature +* +*******************************************************************************/ +#ifndef XIL_FSBL_H +#define XIL_FSBL_H + +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ +#include "xil_io.h" +#include "xparameters.h" +#include "xpseudo_asm.h" +#include "xil_printf.h" +#include "pcap.h" +#include "fsbl_debug.h" +#include "ps7_init.h" +#ifdef FSBL_PERF +#include "xtime_l.h" +#include <stdio.h> +#endif + + +/************************** Constant Definitions *****************************/ +/* + * SDK release version + */ +#define SDK_RELEASE_VER 14 +#define SDK_SUB_VER 7 +#define SDK_RELEASE_YEAR 2013 +#define SDK_RELEASE_QUARTER 3 + +#define WORD_LENGTH_SHIFT 2 + +/* + * On a Successful handoff to an application FSBL sets this SUCCESS code + */ +#define SUCCESSFUL_HANDOFF 0x1 /* Successful Handoff */ + +/* + * Backward compatibility for ps7_init + */ +#ifdef NEW_PS7_ERR_CODE +#define FSBL_PS7_INIT_SUCCESS PS7_INIT_SUCCESS +#else +#define FSBL_PS7_INIT_SUCCESS (1) +#endif + +/* + * ERROR CODES + * The following are the Error codes that FSBL uses + * If the Debug prints are enabled only then the error codes will be + * seen on the com port.Without the debug prints enabled no error codes will + * be visible.There are not saved in any register + * Boot Mode States used for error and status output + * Error codes are defined below + */ +#define ILLEGAL_BOOT_MODE 0xA000 /**< Illegal boot mode */ +#define ILLEGAL_RETURN 0xA001 /**< Illegal return */ +#define PCAP_INIT_FAIL 0xA002 /**< Pcap driver Init Failed */ +#define DECRYPTION_FAIL 0xA003 /**< Decryption Failed */ +#define BITSTREAM_DOWNLOAD_FAIL 0xA004 /**< Bitstream download fail */ +#define DMA_TRANSFER_FAIL 0xA005 /**< DMA Transfer Fail */ +#define INVALID_FLASH_ADDRESS 0xA006 /**< Invalid Flash Address */ +#define DDR_INIT_FAIL 0xA007 /**< DDR Init Fail */ +#define NO_DDR 0xA008 /**< DDR missing */ +#define SD_INIT_FAIL 0xA009 /**< SD Init fail */ +#define NAND_INIT_FAIL 0xA00A /**< Nand Init Fail */ +#define PARTITION_MOVE_FAIL 0xA00B /**< Partition move fail */ +#define AUTHENTICATION_FAIL 0xA00C /**< Authentication fail */ +#define INVALID_HEADER_FAIL 0xA00D /**< Invalid header fail */ +#define GET_HEADER_INFO_FAIL 0xA00E /**< Get header fail */ +#define INVALID_LOAD_ADDRESS_FAIL 0xA00F /**< Invalid load address fail */ +#define PARTITION_CHECKSUM_FAIL 0xA010 /**< Partition checksum fail */ +#define RSA_SUPPORT_NOT_ENABLED_FAIL 0xA011 /**< RSA not enabled fail */ +#define PS7_INIT_FAIL 0xA012 /**< ps7 Init Fail */ +/* + * FSBL Exception error codes + */ +#define EXCEPTION_ID_UNDEFINED_INT 0xA301 /**< Undefined INT Exception */ +#define EXCEPTION_ID_SWI_INT 0xA302 /**< SWI INT Exception */ +#define EXCEPTION_ID_PREFETCH_ABORT_INT 0xA303 /**< Prefetch Abort xception */ +#define EXCEPTION_ID_DATA_ABORT_INT 0xA304 /**< Data Abort Exception */ +#define EXCEPTION_ID_IRQ_INT 0xA305 /**< IRQ Exception Occurred */ +#define EXCEPTION_ID_FIQ_INT 0xA306 /**< FIQ Exception Occurred */ + +/* + * FSBL hook routine failures + */ +#define FSBL_HANDOFF_HOOK_FAIL 0xA401 /**< FSBL handoff hook failed */ +#define FSBL_BEFORE_BSTREAM_HOOK_FAIL 0xA402 /**< FSBL before bit stream + download hook failed */ +#define FSBL_AFTER_BSTREAM_HOOK_FAIL 0xA403 /**< FSBL after bitstream + download hook failed */ + +/* + * Watchdog related Error codes + */ +#define WDT_RESET_OCCURED 0xA501 /**< WDT Reset happened in FSBL */ +#define WDT_INIT_FAIL 0xA502 /**< WDT driver INIT failed */ + +/* + * SLCR Registers + */ +#define PS_RST_CTRL_REG (XPS_SYS_CTRL_BASEADDR + 0x200) +#define FPGA_RESET_REG (XPS_SYS_CTRL_BASEADDR + 0x240) +#define RESET_REASON_REG (XPS_SYS_CTRL_BASEADDR + 0x250) +#define RESET_REASON_CLR (XPS_SYS_CTRL_BASEADDR + 0x254) +#define REBOOT_STATUS_REG (XPS_SYS_CTRL_BASEADDR + 0x258) +#define BOOT_MODE_REG (XPS_SYS_CTRL_BASEADDR + 0x25C) +#define PS_LVL_SHFTR_EN (XPS_SYS_CTRL_BASEADDR + 0x900) + +/* + * Efuse Status Register + */ +#define EFUSE_STATUS_REG (0xF800D010) /**< Efuse Status Register */ +#define EFUSE_STATUS_RSA_ENABLE_MASK (0x400) /**< Status of RSA enable */ + +/* + * PS reset control register define + */ +#define PS_RST_MASK 0x1 /**< PS software reset */ + +/* + * SLCR BOOT Mode Register defines + */ +#define BOOT_MODES_MASK 0x00000007 /**< FLASH types */ + +/* + * Boot Modes + */ +#define JTAG_MODE 0x00000000 /**< JTAG Boot Mode */ +#define QSPI_MODE 0x00000001 /**< QSPI Boot Mode */ +#define NOR_FLASH_MODE 0x00000002 /**< NOR Boot Mode */ +#define NAND_FLASH_MODE 0x00000004 /**< NAND Boot Mode */ +#define SD_MODE 0x00000005 /**< SD Boot Mode */ +#define MMC_MODE 0x00000006 /**< MMC Boot Device */ + +#define RESET_REASON_SRST 0x00000020 /**< Reason for reset is SRST */ +#define RESET_REASON_SWDT 0x00000001 /**< Reason for reset is SWDT */ + +/* + * Golden image offset + */ +#define GOLDEN_IMAGE_OFFSET 0x8000 + +/* + * Silicon Version + */ +#define SILICON_VERSION_1 0 +#define SILICON_VERSION_2 1 +#define SILICON_VERSION_3 2 +#define SILICON_VERSION_3_1 3 + +/* + * DDR start address for storing the data temporarily(1M) + * Need to finalize correct logic + */ +#ifdef XPAR_PS7_DDR_0_S_AXI_BASEADDR +#define DDR_START_ADDR XPAR_PS7_DDR_0_S_AXI_BASEADDR +#define DDR_END_ADDR XPAR_PS7_DDR_0_S_AXI_HIGHADDR +#else +/* + * In case of PL DDR, this macros defined based PL DDR address + */ +#define DDR_START_ADDR 0x00 +#define DDR_END_ADDR 0x00 +#endif + +#define DDR_TEMP_START_ADDR DDR_START_ADDR +/* + * DDR test pattern + */ +#define DDR_TEST_PATTERN 0xAA55AA55 +#define DDR_TEST_OFFSET 0x100000 +/* + * + */ +#define QSPI_DUAL_FLASH_SIZE 0x2000000; /*32MB*/ +#define QSPI_SINGLE_FLASH_SIZE 0x1000000; /*16MB*/ +#define NAND_FLASH_SIZE 0x8000000; /*128MB*/ +#define NOR_FLASH_SIZE 0x2000000; /*32MB*/ +#define LQSPI_CFG_OFFSET 0xA0 +#define LQSPI_CFG_DUAL_FLASH_MASK 0x40000000 + +/* + * These are the SLCR lock and unlock macros + */ +#define SlcrUnlock() Xil_Out32(XPS_SYS_CTRL_BASEADDR + 0x08, 0xDF0DDF0D) +#define SlcrLock() Xil_Out32(XPS_SYS_CTRL_BASEADDR + 0x04, 0x767B767B) + +#define IMAGE_HEADER_CHECKSUM_COUNT 10 + +/* Boot ROM Image defines */ +#define IMAGE_WIDTH_CHECK_OFFSET (0x020) /**< 0xaa995566 Width Detection word */ +#define IMAGE_IDENT_OFFSET (0x024) /**< 0x584C4E58 "XLNX" */ +#define IMAGE_ENC_FLAG_OFFSET (0x028) /**< 0xA5C3C5A3 */ +#define IMAGE_USR_DEF_OFFSET (0x02C) /**< undefined could be used as */ +#define IMAGE_SOURCE_ADDR_OFFSET (0x030) /**< start address of image */ +#define IMAGE_BYTE_LEN_OFFSET (0x034) /**< length of image> in bytes */ +#define IMAGE_DEST_ADDR_OFFSET (0x038) /**< destination address in OCM */ +#define IMAGE_EXECUTE_ADDR_OFFSET (0x03c) /**< address to start executing at */ +#define IMAGE_TOT_BYTE_LEN_OFFSET (0x040) /**< total length of image in bytes */ +#define IMAGE_QSPI_CFG_WORD_OFFSET (0x044) /**< QSPI configuration data */ +#define IMAGE_CHECKSUM_OFFSET (0x048) /**< Header Checksum offset */ +#define IMAGE_IDENT (0x584C4E58) /**< XLNX pattern */ + +/* Reboot status register defines: + * 0xF0000000 for FSBL fallback mask to notify Boot Rom + * 0x60000000 for FSBL to mark that FSBL has not handoff yet + * 0x00FFFFFF for user application to use across soft reset + */ +#define FSBL_FAIL_MASK 0xF0000000 +#define FSBL_IN_MASK 0x60000000 + +/* The address that holds the base address for the image Boot ROM found */ +#define BASEADDR_HOLDER 0xFFFFFFF8 + +/**************************** Type Definitions *******************************/ + +/************************** Function Prototypes ******************************/ + +void OutputStatus(u32 State); +void FsblFallback(void); + +int FsblSetNextPartition(int Num); +void *(memcpy_rom)(void * s1, const void * s2, u32 n); +char *strcpy_rom(char *Dest, const char *Src); + +void ClearFSBLIn(void); +void MarkFSBLIn(void); +void FsblHandoff(u32 FsblStartAddr); +u32 GetResetReason(void); + +#ifdef FSBL_PERF +void FsblGetGlobalTime (XTime tCur); +void FsblMeasurePerfTime (XTime tCur, XTime tEnd); +#endif +void GetSiliconVersion(void); +void FsblHandoffExit(u32 FsblStartAddr); +void FsblHandoffJtagExit(); +/************************** Variable Definitions *****************************/ +extern int SkipPartition; + +/***************** Macros (Inline Functions) Definitions *********************/ + +#ifdef __cplusplus +} +#endif + +#endif /* end of protection macro */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/fsbl_debug.h b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_debug.h new file mode 100644 index 0000000000000000000000000000000000000000..a03cf621695cd4a7fed8a90bc3f66ecb1f8d81e9 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_debug.h @@ -0,0 +1,98 @@ +/************************************************************** + * (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. + * + * This file contains confidential and proprietary information + * of Xilinx, Inc. and is protected under U.S. and + * international copyright and other intellectual property + * laws. + * + * DISCLAIMER + * This disclaimer is not a license and does not grant any + * rights to the materials distributed herewith. Except as + * otherwise provided in a valid license issued to you by + * Xilinx, and to the maximum extent permitted by applicable + * law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND + * WITH ALL FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES + * AND CONDITIONS, EXPRESS, IMPLIED, OR STATUTORY, INCLUDING + * BUT NOT LIMITED TO WARRANTIES OF MERCHANTABILITY, NON- + * INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; and + * (2) Xilinx shall not be liable (whether in contract or tort, + * including negligence, or under any other theory of + * liability) for any loss or damage of any kind or nature + * related to, arising under or in connection with these + * materials, including for any direct, or any indirect, + * special, incidental, or consequential loss or damage + * (including loss of data, profits, goodwill, or any type of + * loss or damage suffered as a result of any action brought + * by a third party) even if such damage or loss was + * reasonably foreseeable or Xilinx had been advised of the + * possibility of the same. + * + * CRITICAL APPLICATIONS + * Xilinx products are not designed or intended to be fail- + * safe, or for use in any application requiring fail-safe + * performance, such as life-support or safety devices or + * systems, Class III medical devices, nuclear facilities, + * applications related to the deployment of airbags, or any + * other applications that could lead to death, personal + * injury, or severe property or environmental damage + * (individually and collectively, "Critical + * Applications"). Customer assumes the sole risk and + * liability of any use of Xilinx products in Critical + * Applications, subject only to applicable laws and + * regulations governing limitations on product liability. + * + * THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS + * PART OF THIS FILE AT ALL TIMES. +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file fsbl_debug.h +* +* This file contains the debug verbose information for FSBL print functionality +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 3.00a mb 01/09/12 Initial release +* +* </pre> +* +* @note +* +******************************************************************************/ + +#ifndef _FSBL_DEBUG_H +#define _FSBL_DEBUG_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#define DEBUG_GENERAL 0x00000001 /* general debug messages */ +#define DEBUG_INFO 0x00000002 /* More debug information */ + +#if defined (FSBL_DEBUG_INFO) +#define fsbl_dbg_current_types ((DEBUG_INFO) | (DEBUG_GENERAL)) +#elif defined (FSBL_DEBUG) +#define fsbl_dbg_current_types (DEBUG_GENERAL) +#else +#define fsbl_dbg_current_types 0 +#endif + +#ifdef STDOUT_BASEADDRESS +#define fsbl_printf(type,...) \ + if (((type) & fsbl_dbg_current_types)) {xil_printf (__VA_ARGS__); } +#else +#define fsbl_printf(type, ...) +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* _FSBL_DEBUG_H */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/fsbl_handoff.S b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_handoff.S new file mode 100644 index 0000000000000000000000000000000000000000..8aa30897745719594c39cea15aebee2e160cceb5 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_handoff.S @@ -0,0 +1,115 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file handoff.S +* +* Contains the code that does the handoff to the loaded application. This +* code lives high in the ROM. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date.word Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 03/01/10 Initial release +* +* </pre> +* +* @note +* Assumes that the starting address of the FSBL is provided by the calling routine +* in R0. +* +******************************************************************************/ + +.globl FsblHandoffJtagExit + +.globl FsblHandoffExit + +.section .handoff,"axS" + +/***************************** Include Files *********************************/ + +/************************** Constant Definitions *****************************/ + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ + +/************************** Variable Definitions *****************************/ + +FsblHandoffJtagExit: + mcr 15,0,r0,cr7,cr5,0 /* Invalidate Instruction cache */ + mcr 15,0,r0,cr7,cr5,6 /* Invalidate branch predictor array */ + + dsb + isb /* make sure it completes */ + + ldr r4, =0 + mcr 15,0,r4,cr1,cr0,0 /* disable the ICache and MMU */ + + isb /* make sure it completes */ +Loop: + wfe + b Loop + +FsblHandoffExit: + mov lr, r0 /* move the destination address into link register */ + + mcr 15,0,r0,cr7,cr5,0 /* Invalidate Instruction cache */ + mcr 15,0,r0,cr7,cr5,6 /* Invalidate branch predictor array */ + + dsb + isb /* make sure it completes */ + + ldr r4, =0 + mcr 15,0,r4,cr1,cr0,0 /* disable the ICache and MMU */ + + isb /* make sure it completes */ + + + bx lr /* force the switch, destination should have been in r0 */ + +.Ldone: b .Ldone /* Paranoia: we should never get here */ +.end diff --git a/quad/xsdk_workspace/zybo_fsbl/src/fsbl_hooks.c b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_hooks.c new file mode 100644 index 0000000000000000000000000000000000000000..7b27a25e79d5c78438b8d5b4e1b09fcbc8eb2a99 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_hooks.c @@ -0,0 +1,173 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ + +/***************************************************************************** +* +* @file fsbl_hooks.c +* +* This file provides functions that serve as user hooks. The user can add the +* additional functionality required into these routines. This would help retain +* the normal FSBL flow unchanged. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 3.00a np 08/03/12 Initial release +* </pre> +* +* @note +* +******************************************************************************/ + + +#include "fsbl.h" +#include "xstatus.h" +#include "fsbl_hooks.h" + +/************************** Variable Definitions *****************************/ + + +/************************** Function Prototypes ******************************/ + + +/****************************************************************************** +* This function is the hook which will be called before the bitstream download. +* The user can add all the customized code required to be executed before the +* bitstream download to this routine. +* +* @param None +* +* @return +* - XST_SUCCESS to indicate success +* - XST_FAILURE.to indicate failure +* +****************************************************************************/ +u32 FsblHookBeforeBitstreamDload(void) +{ + u32 Status; + + Status = XST_SUCCESS; + + /* + * User logic to be added here. Errors to be stored in the status variable + * and returned + */ + fsbl_printf(DEBUG_INFO,"In FsblHookBeforeBitstreamDload function \r\n"); + + return (Status); +} + +/****************************************************************************** +* This function is the hook which will be called after the bitstream download. +* The user can add all the customized code required to be executed after the +* bitstream download to this routine. +* +* @param None +* +* @return +* - XST_SUCCESS to indicate success +* - XST_FAILURE.to indicate failure +* +****************************************************************************/ +u32 FsblHookAfterBitstreamDload(void) +{ + u32 Status; + + Status = XST_SUCCESS; + + /* + * User logic to be added here. + * Errors to be stored in the status variable and returned + */ + fsbl_printf(DEBUG_INFO, "In FsblHookAfterBitstreamDload function \r\n"); + + return (Status); +} + +/****************************************************************************** +* This function is the hook which will be called before the FSBL does a handoff +* to the application. The user can add all the customized code required to be +* executed before the handoff to this routine. +* +* @param None +* +* @return +* - XST_SUCCESS to indicate success +* - XST_FAILURE.to indicate failure +* +****************************************************************************/ +u32 FsblHookBeforeHandoff(void) +{ + u32 Status; + + Status = XST_SUCCESS; + + /* + * User logic to be added here. + * Errors to be stored in the status variable and returned + */ + fsbl_printf(DEBUG_INFO,"In FsblHookBeforeHandoff function \r\n"); + + return (Status); +} + + +/****************************************************************************** +* This function is the hook which will be called in case FSBL fall back +* +* @param None +* +* @return None +* +****************************************************************************/ +void FsblHookFallback(void) +{ + /* + * User logic to be added here. + * Errors to be stored in the status variable and returned + */ + fsbl_printf(DEBUG_INFO,"In FsblHookFallback function \r\n"); + while(1); +} + + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/fsbl_hooks.h b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_hooks.h new file mode 100644 index 0000000000000000000000000000000000000000..6ba5c039fb67ec6696820987f7ad7d87f558deae --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/fsbl_hooks.h @@ -0,0 +1,90 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file fsbl_hooks.h +* +* Contains the function prototypes, defines and macros required by fsbl_hooks.c +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 3.00a np/mb 10/08/12 Initial release +* Corrected the prototype +* +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef FSBL_HOOKS_H_ +#define FSBL_HOOKS_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ +#include "fsbl.h" + + +/************************** Function Prototypes ******************************/ + +/* FSBL hook function which is called before bitstream download */ +u32 FsblHookBeforeBitstreamDload(void); + +/* FSBL hook function which is called after bitstream download */ +u32 FsblHookAfterBitstreamDload(void); + +/* FSBL hook function which is called before handoff to the application */ +u32 FsblHookBeforeHandoff(void); + +/* FSBL hook function which is called in FSBL fallback */ +void FsblHookFallback(void); + +#ifdef __cplusplus +} +#endif + +#endif /* end of protection macro */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/image_mover.c b/quad/xsdk_workspace/zybo_fsbl/src/image_mover.c new file mode 100644 index 0000000000000000000000000000000000000000..81ab06a5135fffa9f2bcf9117b611c323326f447 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/image_mover.c @@ -0,0 +1,1301 @@ +/****************************************************************************** +* +* (c) Copyright 2011-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file image_mover.c +* +* Move partitions to either DDR to execute or to program FPGA. +* It performs partition walk. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a jz 05/24/11 Initial release +* 2.00a jz 06/30/11 Updated partition header defs for 64-byte +* alignment change in data2mem tool +* 2.00a mb 05/25/12 Updated for standalone based bsp FSBL +* Nand/SD encryption and review comments +* 3.00a np 08/30/12 Added FSBL user hook calls +* (before and after bitstream download.) +* 4.00a sgd 02/28/13 Fix for CR#691148 +* Fix for CR#695578 +* +* 4.00a sgd 04/23/13 Fix for CR#710128 +* 5.00a kc 07/30/13 Fix for CR#724165 +* Fix for CR#724166 +* Fix for CR#732062 +* +* </pre> +* +* @note +* A partition is either an executable or a bitstream to program FPGA +* +******************************************************************************/ + +/***************************** Include Files *********************************/ +#include "fsbl.h" +#include "image_mover.h" +#include "xil_printf.h" +#include "xreg_cortexa9.h" +#include "pcap.h" +#include "fsbl_hooks.h" +#include "md5.h" + +#ifdef XPAR_XWDTPS_0_BASEADDR +#include "xwdtps.h" +#endif + +#ifdef RSA_SUPPORT +#include "rsa.h" +#endif +/************************** Constant Definitions *****************************/ + +/* We are 32-bit machine */ +#define MAXIMUM_IMAGE_WORD_LEN 0x40000000 +#define MD5_CHECKSUM_SIZE 16 + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ +u32 ValidateParition(u32 StartAddr, u32 Length, u32 ChecksumOffset); +u32 GetPartitionChecksum(u32 ChecksumOffset, u8 *Checksum); +u32 CalcPartitionChecksum(u32 SourceAddr, u32 DataLength, u8 *Checksum); + +/************************** Variable Definitions *****************************/ +/* + * Partition information flags + */ +u8 EncryptedPartitionFlag; +u8 PLPartitionFlag; +u8 PSPartitionFlag; +u8 SignedPartitionFlag; +u8 PartitionChecksumFlag; +u8 BitstreamFlag; +u8 ApplicationFlag; + +u32 ExecutionAddress; +ImageMoverType MoveImage; + +/* + * Header array + */ +PartHeader PartitionHeader[MAX_PARTITION_NUMBER]; +u32 PartitionCount; +u32 FsblLength; + +#ifdef XPAR_XWDTPS_0_BASEADDR +extern XWdtPs Watchdog; /* Instance of WatchDog Timer */ +#endif + +extern u32 Silicon_Version; +extern u32 FlashReadBaseAddress; +extern u8 LinearBootDeviceFlag; +extern XDcfg *DcfgInstPtr; + +/*****************************************************************************/ +/** +* +* This function +* +* @param +* +* @return +* +* +* @note None +* +****************************************************************************/ +u32 LoadBootImage(void) +{ + u32 RebootStatusRegister = 0; + u32 MultiBootReg = 0; + u32 ImageStartAddress = 0; + u32 PartitionNum; + u32 PartitionDataLength; + u32 PartitionImageLength; + u32 PartitionTotalSize; + u32 PartitionExecAddr; + u32 PartitionAttr; + u32 ExecAddress = 0; + u32 PartitionLoadAddr; + u32 PartitionStartAddr; + u32 PartitionChecksumOffset; + u8 ExecAddrFlag = 0 ; + u32 Status; + PartHeader *HeaderPtr; + u32 EfuseStatusRegValue; +#ifdef RSA_SUPPORT + u32 HeaderSize; +#endif + /* + * Resetting the Flags + */ + BitstreamFlag = 0; + ApplicationFlag = 0; + + RebootStatusRegister = Xil_In32(REBOOT_STATUS_REG); + fsbl_printf(DEBUG_INFO, + "Reboot status register: 0x%08x\r\n",RebootStatusRegister); + + if (Silicon_Version == SILICON_VERSION_1) { + /* + * Clear out fallback mask from previous run + * We start from the first partition again + */ + if ((RebootStatusRegister & FSBL_FAIL_MASK) == + FSBL_FAIL_MASK) { + fsbl_printf(DEBUG_INFO, + "Reboot status shows previous run falls back\r\n"); + RebootStatusRegister &= ~(FSBL_FAIL_MASK); + Xil_Out32(REBOOT_STATUS_REG, RebootStatusRegister); + } + + /* + * Read the image start address + */ + ImageStartAddress = *(u32 *)BASEADDR_HOLDER; + } else { + /* + * read the multiboot register + */ + MultiBootReg = XDcfg_ReadReg(DcfgInstPtr->Config.BaseAddr, + XDCFG_MULTIBOOT_ADDR_OFFSET); + + fsbl_printf(DEBUG_INFO,"Multiboot Register: 0x%08x\r\n",MultiBootReg); + + /* + * Compute the image start address + */ + ImageStartAddress = (MultiBootReg & PCAP_MBOOT_REG_REBOOT_OFFSET_MASK) + * GOLDEN_IMAGE_OFFSET; + } + + fsbl_printf(DEBUG_INFO,"Image Start Address: 0x%08x\r\n",ImageStartAddress); + + /* + * Get partitions header information + */ + Status = GetPartitionHeaderInfo(ImageStartAddress); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "Partition Header Load Failed\r\n"); + OutputStatus(GET_HEADER_INFO_FAIL); + FsblFallback(); + } + + /* + * RSA is not implemented in 1.0 and 2.0 + * silicon + */ + if ((Silicon_Version != SILICON_VERSION_1) && + (Silicon_Version != SILICON_VERSION_2)) { + /* + * Read Efuse Status Register + */ + EfuseStatusRegValue = Xil_In32(EFUSE_STATUS_REG); + if (EfuseStatusRegValue & EFUSE_STATUS_RSA_ENABLE_MASK) { + fsbl_printf(DEBUG_GENERAL,"RSA enabled for Chip\r\n"); +#ifdef RSA_SUPPORT + /* + * Set the Ppk + */ + SetPpk(); + + /* + * Read partition header with signature + */ + Status = GetImageHeaderAndSignature(ImageStartAddress, + (u32 *)DDR_TEMP_START_ADDR); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, + "Read Partition Header signature Failed\r\n"); + OutputStatus(GET_HEADER_INFO_FAIL); + FsblFallback(); + } + HeaderSize=TOTAL_HEADER_SIZE+RSA_SIGNATURE_SIZE; + + Status = AuthenticatePartition((u8 *)DDR_TEMP_START_ADDR, HeaderSize); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, + "Partition Header signature Failed\r\n"); + OutputStatus(GET_HEADER_INFO_FAIL); + FsblFallback(); + } +#else + /* + * In case user not enabled RSA authentication feature + */ + fsbl_printf(DEBUG_GENERAL,"RSA_SUPPORT_NOT_ENABLED_FAIL\r\n"); + OutputStatus(RSA_SUPPORT_NOT_ENABLED_FAIL); + FsblFallback(); +#endif + } + } + +#ifdef MMC_SUPPORT + /* + * In case of MMC support + * boot image preset in MMC will not have FSBL partition + */ + PartitionNum = 0; +#else + /* + * First partition header was ignored by FSBL + * As it contain FSBL partition information + */ + PartitionNum = 1; +#endif + + while (PartitionNum < PartitionCount) { + + fsbl_printf(DEBUG_INFO, "Partition Number: %d\r\n", PartitionNum); + + HeaderPtr = &PartitionHeader[PartitionNum]; + + /* + * Print partition header information + */ + HeaderDump(HeaderPtr); + + /* + * Validate partition header + */ + Status = ValidateHeader(HeaderPtr); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "INVALID_HEADER_FAIL\r\n"); + OutputStatus(INVALID_HEADER_FAIL); + FsblFallback(); + } + + /* + * Load partition header information in to local variables + */ + PartitionDataLength = HeaderPtr->DataWordLen; + PartitionImageLength = HeaderPtr->ImageWordLen; + PartitionExecAddr = HeaderPtr->ExecAddr; + PartitionAttr = HeaderPtr->PartitionAttr; + PartitionLoadAddr = HeaderPtr->LoadAddr; + PartitionChecksumOffset = HeaderPtr->CheckSumOffset; + PartitionStartAddr = HeaderPtr->PartitionStart; + PartitionTotalSize = HeaderPtr->PartitionWordLen; + + + if (PartitionAttr & ATTRIBUTE_PL_IMAGE_MASK) { + fsbl_printf(DEBUG_INFO, "Bitstream\r\n"); + PLPartitionFlag = 1; + PSPartitionFlag = 0; + BitstreamFlag = 1; + if (ApplicationFlag == 1) { +#ifdef STDOUT_BASEADDRESS + xil_printf("\r\nFSBL Warning !!!" + "Bitstream not loaded into PL\r\n"); + xil_printf("Partition order invalid\r\n"); +#endif + break; + } + } + + if (PartitionAttr & ATTRIBUTE_PS_IMAGE_MASK) { + fsbl_printf(DEBUG_INFO, "Application\r\n"); + PSPartitionFlag = 1; + PLPartitionFlag = 0; + ApplicationFlag = 1; + } + + /* + * Encrypted partition will have different value + * for Image length and data length + */ + if (PartitionDataLength != PartitionImageLength) { + fsbl_printf(DEBUG_INFO, "Encrypted\r\n"); + EncryptedPartitionFlag = 1; + } else { + EncryptedPartitionFlag = 0; + } + + /* + * Check for partition checksum check + */ + if (PartitionAttr & ATTRIBUTE_CHECKSUM_TYPE_MASK) { + PartitionChecksumFlag = 1; + } else { + PartitionChecksumFlag = 0; + } + + /* + * RSA signature check + */ + if (PartitionAttr & ATTRIBUTE_RSA_PRESENT_MASK) { + fsbl_printf(DEBUG_INFO, "RSA Signed\r\n"); + SignedPartitionFlag = 1; + } else { + SignedPartitionFlag = 0; + } + + /* + * Load address check + * Loop will break when PS load address zero and partition is + * un-signed or un-encrypted + */ + if ((PSPartitionFlag == 1) && (PartitionLoadAddr < DDR_START_ADDR)) { + if ((PartitionLoadAddr == 0) && + (!((SignedPartitionFlag == 1) || + (EncryptedPartitionFlag == 1)))) { + break; + } else { + fsbl_printf(DEBUG_GENERAL, + "INVALID_LOAD_ADDRESS_FAIL\r\n"); + OutputStatus(INVALID_LOAD_ADDRESS_FAIL); + FsblFallback(); + } + } + + if (PSPartitionFlag && (PartitionLoadAddr > DDR_END_ADDR)) { + fsbl_printf(DEBUG_GENERAL, + "INVALID_LOAD_ADDRESS_FAIL\r\n"); + OutputStatus(INVALID_LOAD_ADDRESS_FAIL); + FsblFallback(); + } + + /* + * Load execution address of first PS partition + */ + if (PSPartitionFlag && (!ExecAddrFlag)) { + ExecAddrFlag++; + ExecAddress = PartitionExecAddr; + } + + /* + * FSBL user hook call before bitstream download + */ + if (PLPartitionFlag) { + Status = FsblHookBeforeBitstreamDload(); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"FSBL_BEFORE_BSTREAM_HOOK_FAIL\r\n"); + OutputStatus(FSBL_BEFORE_BSTREAM_HOOK_FAIL); + FsblFallback(); + } + } + + /* + * Move partitions from boot device + */ + Status = PartitionMove(ImageStartAddress, HeaderPtr); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"PARTITION_MOVE_FAIL\r\n"); + OutputStatus(PARTITION_MOVE_FAIL); + FsblFallback(); + } + + if ((SignedPartitionFlag) || (PartitionChecksumFlag)) { + if(PLPartitionFlag) { + /* + * PL partition loaded in to DDR temporary address + * for authentication and checksum verification + */ + PartitionStartAddr = DDR_TEMP_START_ADDR; + } else { + PartitionStartAddr = PartitionLoadAddr; + } + + if (PartitionChecksumFlag) { + /* + * Validate the partition data with checksum + */ + Status = ValidateParition(PartitionStartAddr, + (PartitionTotalSize << WORD_LENGTH_SHIFT), + (PartitionChecksumOffset << WORD_LENGTH_SHIFT)); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"PARTITION_CHECKSUM_FAIL\r\n"); + OutputStatus(PARTITION_CHECKSUM_FAIL); + FsblFallback(); + } + + fsbl_printf(DEBUG_INFO, "Partition Validation Done\r\n"); + } + + /* + * Authentication Partition + */ + if (SignedPartitionFlag == 1 ) { +#ifdef RSA_SUPPORT + Status = AuthenticatePartition((u8*)PartitionStartAddr, + (PartitionTotalSize << WORD_LENGTH_SHIFT)); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"AUTHENTICATION_FAIL\r\n"); + OutputStatus(AUTHENTICATION_FAIL); + FsblFallback(); + } + fsbl_printf(DEBUG_INFO,"Authentication Done\r\n"); +#else + /* + * In case user not enabled RSA authentication feature + */ + fsbl_printf(DEBUG_GENERAL,"RSA_SUPPORT_NOT_ENABLED_FAIL\r\n"); + OutputStatus(RSA_SUPPORT_NOT_ENABLED_FAIL); + FsblFallback(); +#endif + } + + /* + * Decrypt PS partition + */ + if (EncryptedPartitionFlag && PSPartitionFlag) { + Status = DecryptPartition(PartitionStartAddr, + PartitionDataLength, + PartitionImageLength); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"DECRYPTION_FAIL\r\n"); + OutputStatus(DECRYPTION_FAIL); + FsblFallback(); + } + } + + /* + * Load Signed PL partition in Fabric + */ + if (PLPartitionFlag) { + Status = PcapLoadPartition((u32*)PartitionStartAddr, + (u32*)PartitionLoadAddr, + PartitionImageLength, + PartitionDataLength, + EncryptedPartitionFlag); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"BITSTREAM_DOWNLOAD_FAIL\r\n"); + OutputStatus(BITSTREAM_DOWNLOAD_FAIL); + FsblFallback(); + } + } + } + + + /* + * FSBL user hook call after bitstream download + */ + if (PLPartitionFlag) { + Status = FsblHookAfterBitstreamDload(); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"FSBL_AFTER_BSTREAM_HOOK_FAIL\r\n"); + OutputStatus(FSBL_AFTER_BSTREAM_HOOK_FAIL); + FsblFallback(); + } + } + /* + * Increment partition number + */ + PartitionNum++; + } + + return ExecAddress; +} + +/*****************************************************************************/ +/** +* +* This function loads all partition header information in global array +* +* @param ImageAddress is the start address of the image +* +* @return - XST_SUCCESS if Get partition Header information successful +* - XST_FAILURE if Get Partition Header information failed +* +* @note None +* +****************************************************************************/ +u32 GetPartitionHeaderInfo(u32 ImageBaseAddress) +{ + u32 PartitionHeaderOffset; + u32 Status; + + + /* + * Get the length of the FSBL from BootHeader + */ + Status = GetFsblLength(ImageBaseAddress, &FsblLength); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "Get Header Start Address Failed\r\n"); + return XST_FAILURE; + } + + /* + * Get the start address of the partition header table + */ + Status = GetPartitionHeaderStartAddr(ImageBaseAddress, + &PartitionHeaderOffset); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "Get Header Start Address Failed\r\n"); + return XST_FAILURE; + } + + /* + * Header offset on flash + */ + PartitionHeaderOffset += ImageBaseAddress; + + fsbl_printf(DEBUG_INFO,"Partition Header Offset:0x%08x\r\n", + PartitionHeaderOffset); + + /* + * Load all partitions header data in to global variable + */ + Status = LoadPartitionsHeaderInfo(PartitionHeaderOffset, + &PartitionHeader[0]); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "Header Information Load Failed\r\n"); + return XST_FAILURE; + } + + /* + * Get partitions count from partitions header information + */ + PartitionCount = GetPartitionCount(&PartitionHeader[0]); + + fsbl_printf(DEBUG_INFO, "Partition Count: %d\r\n", PartitionCount); + + /* + * Partition Count check + */ + if (PartitionCount >= MAX_PARTITION_NUMBER) { + fsbl_printf(DEBUG_GENERAL, "Invalid Partition Count\r\n"); + return XST_FAILURE; + + } else if (PartitionCount <= 1) { + fsbl_printf(DEBUG_GENERAL, "There is no partition to load\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/*****************************************************************************/ +/** +* +* This function goes to the partition header of the specified partition +* +* @param ImageAddress is the start address of the image +* +* @return Offset Partition header address of the image +* +* @return - XST_SUCCESS if Get Partition Header start address successful +* - XST_FAILURE if Get Partition Header start address failed +* +* @note None +* +****************************************************************************/ +u32 GetPartitionHeaderStartAddr(u32 ImageAddress, u32 *Offset) +{ + u32 Status; + + Status = MoveImage(ImageAddress + IMAGE_PHDR_OFFSET, (u32)Offset, 4); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"Move Image failed\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + +/*****************************************************************************/ +/** +* +* This function goes to the partition header of the specified partition +* +* @param ImageAddress is the start address of the image +* +* @return Offset to Image header table address of the image +* +* @return - XST_SUCCESS if Get Partition Header start address successful +* - XST_FAILURE if Get Partition Header start address failed +* +* @note None +* +****************************************************************************/ +u32 GetImageHeaderStartAddr(u32 ImageAddress, u32 *Offset) +{ + u32 Status; + + Status = MoveImage(ImageAddress + IMAGE_HDR_OFFSET, (u32)Offset, 4); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"Move Image failed\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} +/*****************************************************************************/ +/** +* +* This function gets the length of the FSBL +* +* @param ImageAddress is the start address of the image +* +* @return FsblLength is the length of the fsbl +* +* @return - XST_SUCCESS if fsbl length reading is successful +* - XST_FAILURE if fsbl length reading failed +* +* @note None +* +****************************************************************************/ +u32 GetFsblLength(u32 ImageAddress, u32 *FsblLength) +{ + u32 Status; + + Status = MoveImage(ImageAddress + IMAGE_TOT_BYTE_LEN_OFFSET, + (u32)FsblLength, 4); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"Move Image failed reading FsblLength\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + +#ifdef RSA_SUPPORT +/*****************************************************************************/ +/** +* +* This function goes to read the image headers and its signature. Image +* header consists of image header table, image headers, partition +* headers +* +* @param ImageBaseAddress is the start address of the image header +* +* @return Offset Partition header address of the image +* +* @return - XST_SUCCESS if Get Partition Header start address successful +* - XST_FAILURE if Get Partition Header start address failed +* +* @note None +* +****************************************************************************/ +u32 GetImageHeaderAndSignature(u32 ImageBaseAddress, u32 *Offset) +{ + u32 Status; + u32 ImageHeaderOffset; + + /* + * Get the start address of the partition header table + */ + Status = GetImageHeaderStartAddr(ImageBaseAddress, &ImageHeaderOffset); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "Get Header Start Address Failed\r\n"); + return XST_FAILURE; + } + + Status = MoveImage(ImageBaseAddress+ImageHeaderOffset, (u32)Offset, + TOTAL_HEADER_SIZE + RSA_SIGNATURE_SIZE); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"Move Image failed\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} +#endif +/*****************************************************************************/ +/** +* +* This function get the header information of the all the partitions and load into +* global array +* +* @param PartHeaderOffset Offset address where the header information present +* +* @param Header Partition header pointer +* +* @return - XST_SUCCESS if Load Partitions Header information successful +* - XST_FAILURE if Load Partitions Header information failed +* +* @note None +* +****************************************************************************/ +u32 LoadPartitionsHeaderInfo(u32 PartHeaderOffset, PartHeader *Header) +{ + u32 Status; + + Status = MoveImage(PartHeaderOffset, (u32)Header, sizeof(PartHeader)*MAX_PARTITION_NUMBER); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"Move Image failed\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/*****************************************************************************/ +/** +* +* This function dumps the partition header. +* +* @param Header Partition header pointer +* +* @return None +* +* @note None +* +******************************************************************************/ +void HeaderDump(PartHeader *Header) +{ + fsbl_printf(DEBUG_INFO, "Header Dump\r\n"); + fsbl_printf(DEBUG_INFO, "Image Word Len: 0x%08x\r\n", + Header->ImageWordLen); + fsbl_printf(DEBUG_INFO, "Data Word Len: 0x%08x\r\n", + Header->DataWordLen); + fsbl_printf(DEBUG_INFO, "Partition Word Len:0x%08x\r\n", + Header->PartitionWordLen); + fsbl_printf(DEBUG_INFO, "Load Addr: 0x%08x\r\n", + Header->LoadAddr); + fsbl_printf(DEBUG_INFO, "Exec Addr: 0x%08x\r\n", + Header->ExecAddr); + fsbl_printf(DEBUG_INFO, "Partition Start: 0x%08x\r\n", + Header->PartitionStart); + fsbl_printf(DEBUG_INFO, "Partition Attr: 0x%08x\r\n", + Header->PartitionAttr); + fsbl_printf(DEBUG_INFO, "Partition Checksum Offset: 0x%08x\r\n", + Header->CheckSumOffset); + fsbl_printf(DEBUG_INFO, "Section Count: 0x%08x\r\n", + Header->SectionCount); + fsbl_printf(DEBUG_INFO, "Checksum: 0x%08x\r\n", + Header->CheckSum); +} + + +/******************************************************************************/ +/** +* +* This function calculates the partitions count from header information +* +* @param Header Partition header pointer +* +* @return Count Partition count +* +* @note None +* +*******************************************************************************/ +u32 GetPartitionCount(PartHeader *Header) +{ + u32 Count=0; + struct HeaderArray *Hap; + + for(Count = 0; Count < MAX_PARTITION_NUMBER; Count++) { + Hap = (struct HeaderArray *)&Header[Count]; + if(IsLastPartition(Hap)!=XST_FAILURE) + break; + } + + return Count; +} + +/******************************************************************************/ +/** +* This function check whether the current partition is the end of partitions +* +* The partition is the end of the partitions if it looks like this: +* 0x00000000 +* 0x00000000 +* .... +* 0x00000000 +* 0x00000000 +* 0xFFFFFFFF +* +* @param H is a pointer to struct HeaderArray +* +* @return +* - XST_SUCCESS if it is the last partition +* - XST_FAILURE if it is not last partition +* +****************************************************************************/ +u32 IsLastPartition(struct HeaderArray *H) +{ + int Index; + + if (H->Fields[PARTITION_HDR_CHECKSUM_WORD_COUNT] != 0xFFFFFFFF) { + return XST_FAILURE; + } + + for (Index = 0; Index < PARTITION_HDR_WORD_COUNT - 1; Index++) { + + if (H->Fields[Index] != 0x0) { + return XST_FAILURE; + } + } + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function validates the partition header. +* +* @param Header Partition header pointer +* +* @return +* - XST_FAILURE if bad header. +* - XST_SUCCESS if successful. +* +* @note None +* +*******************************************************************************/ +u32 ValidateHeader(PartHeader *Header) +{ + struct HeaderArray *Hap; + + Hap = (struct HeaderArray *)Header; + + /* + * If there are no partitions to load, fail + */ + if (IsEmptyHeader(Hap) == XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "IMAGE_HAS_NO_PARTITIONS\r\n"); + return XST_FAILURE; + } + + /* + * Validate partition header checksum + */ + if (ValidatePartitionHeaderChecksum(Hap) != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "PARTITION_HEADER_CORRUPTION\r\n"); + return XST_FAILURE; + } + + /* + * Validate partition data size + */ + if (Header->ImageWordLen > MAXIMUM_IMAGE_WORD_LEN) { + fsbl_printf(DEBUG_GENERAL, "INVALID_PARTITION_LENGTH\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* This function check whether the current partition header is empty. +* A partition header is considered empty if image word length is 0 and the +* last word is 0. +* +* @param H is a pointer to struct HeaderArray +* +* @return +* - XST_SUCCESS , If the partition header is empty +* - XST_FAILURE , If the partition header is NOT empty +* +* @note Caller is responsible to make sure the address is valid. +* +* +****************************************************************************/ +u32 IsEmptyHeader(struct HeaderArray *H) +{ + int Index; + + for (Index = 0; Index < PARTITION_HDR_WORD_COUNT; Index++) { + if (H->Fields[Index] != 0x0) { + return XST_FAILURE; + } + } + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function checks the header checksum If the header checksum is not valid +* XST_FAILURE is returned. +* +* @param H is a pointer to struct HeaderArray +* +* @return +* - XST_SUCCESS is header checksum is ok +* - XST_FAILURE if the header checksum is not correct +* +* @note None. +* +****************************************************************************/ +u32 ValidatePartitionHeaderChecksum(struct HeaderArray *H) +{ + u32 Checksum; + u32 Count; + + Checksum = 0; + + for (Count = 0; Count < PARTITION_HDR_CHECKSUM_WORD_COUNT; Count++) { + /* + * Read the word from the header + */ + Checksum += H->Fields[Count]; + } + + /* + * Invert checksum, last bit of error checking + */ + Checksum ^= 0xFFFFFFFF; + + /* + * Validate the checksum + */ + if (H->Fields[PARTITION_HDR_CHECKSUM_WORD_COUNT] != Checksum) { + fsbl_printf(DEBUG_GENERAL, "Error: Checksum 0x%8.8x != 0x%8.8x\r\n", + Checksum, H->Fields[PARTITION_HDR_CHECKSUM_WORD_COUNT]); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function load the partition from boot device +* +* @param ImageBaseAddress Base address on flash +* @param Header Partition header pointer +* +* @return +* - XST_SUCCESS if partition move successful +* - XST_FAILURE if check failed move failed +* +* @note None +* +*******************************************************************************/ +u32 PartitionMove(u32 ImageBaseAddress, PartHeader *Header) +{ + u32 SourceAddr; + u32 Status; + u8 SecureTransferFlag = 0; + u32 LoadAddr; + u32 ImageWordLen; + u32 DataWordLen; + + SourceAddr = ImageBaseAddress; + SourceAddr += Header->PartitionStart<<WORD_LENGTH_SHIFT; + LoadAddr = Header->LoadAddr; + ImageWordLen = Header->ImageWordLen; + DataWordLen = Header->DataWordLen; + + /* + * Add flash base address for linear boot devices + */ + if (LinearBootDeviceFlag) { + SourceAddr += FlashReadBaseAddress; + } + + /* + * Partition encrypted + */ + if(EncryptedPartitionFlag) { + SecureTransferFlag = 1; + } + + /* + * For Signed partition, Total partition image need to copied to DDR + */ + if (SignedPartitionFlag) { + ImageWordLen = Header->PartitionWordLen; + DataWordLen = Header->PartitionWordLen; + } + + /* + * Encrypted and Signed PS partition need to be loaded on to DDR + * without decryption + */ + if (PSPartitionFlag && + (SignedPartitionFlag || PartitionChecksumFlag) && + EncryptedPartitionFlag) { + SecureTransferFlag = 0; + } + + /* + * CPU is used for data transfer in case of non-linear + * boot device + */ + if (!LinearBootDeviceFlag) { + /* + * PL partition copied to DDR temporary location + */ + if (PLPartitionFlag) { + LoadAddr = DDR_TEMP_START_ADDR; + } + + Status = MoveImage(SourceAddr, + LoadAddr, + (ImageWordLen << WORD_LENGTH_SHIFT)); + if(Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "Move Image Failed\r\n"); + return XST_FAILURE; + } + + /* + * As image present at load address + */ + SourceAddr = LoadAddr; + } + + if ((LinearBootDeviceFlag && PLPartitionFlag && + (SignedPartitionFlag || PartitionChecksumFlag)) || + (LinearBootDeviceFlag && PSPartitionFlag) || + ((!LinearBootDeviceFlag) && PSPartitionFlag && SecureTransferFlag)) { + /* + * PL signed partition copied to DDR temporary location + * using non-secure PCAP for linear boot device + */ + if(PLPartitionFlag){ + SecureTransferFlag = 0; + LoadAddr = DDR_TEMP_START_ADDR; + } + + /* + * Data transfer using PCAP + */ + Status = PcapDataTransfer((u32*)SourceAddr, + (u32*)LoadAddr, + ImageWordLen, + DataWordLen, + SecureTransferFlag); + if(Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "PCAP Data Transfer Failed\r\n"); + return XST_FAILURE; + } + + /* + * As image present at load address + */ + SourceAddr = LoadAddr; + } + + /* + * Load Bitstream partition in to fabric only + * if checksum and authentication bits are not set + */ + if (PLPartitionFlag && (!(SignedPartitionFlag || PartitionChecksumFlag))) { + Status = PcapLoadPartition((u32*)SourceAddr, + (u32*)Header->LoadAddr, + Header->ImageWordLen, + Header->DataWordLen, + EncryptedPartitionFlag); + if(Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL, "PCAP Bitstream Download Failed\r\n"); + return XST_FAILURE; + } + } + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function load the decrypts partition +* +* @param StartAddr Source start address +* @param DataLength Data length in words +* @param ImageLength Image length in words +* +* @return +* - XST_SUCCESS if decryption successful +* - XST_FAILURE if decryption failed +* +* @note None +* +*******************************************************************************/ +u32 DecryptPartition(u32 StartAddr, u32 DataLength, u32 ImageLength) +{ + u32 Status; + u8 SecureTransferFlag =1; + + /* + * Data transfer using PCAP + */ + Status = PcapDataTransfer((u32*)StartAddr, + (u32*)StartAddr, + ImageLength, + DataLength, + SecureTransferFlag); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"PCAP Data Transfer failed \r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + +/******************************************************************************/ +/** +* +* This function Validate Partition Data by using checksum preset in image +* +* @param Partition header pointer +* @param Partition check sum offset +* @return +* - XST_SUCCESS if partition data is ok +* - XST_FAILURE if partition data is corrupted +* +* @note None +* +*******************************************************************************/ +u32 ValidateParition(u32 StartAddr, u32 Length, u32 ChecksumOffset) +{ + u8 Checksum[MD5_CHECKSUM_SIZE]; + u8 CalcChecksum[MD5_CHECKSUM_SIZE]; + u32 Status; + u32 Index; + +#ifdef XPAR_XWDTPS_0_BASEADDR + /* + * Prevent WDT reset + */ + XWdtPs_RestartWdt(&Watchdog); +#endif + + /* + * Get checksum from flash + */ + Status = GetPartitionChecksum(ChecksumOffset, &Checksum[0]); + if(Status != XST_SUCCESS) { + return XST_FAILURE; + } + + fsbl_printf(DEBUG_INFO, "Actual checksum\r\n"); + + for (Index = 0; Index < MD5_CHECKSUM_SIZE; Index++) { + fsbl_printf(DEBUG_INFO, "0x%0x ",Checksum[Index]); + } + + fsbl_printf(DEBUG_INFO, "\r\n"); + + /* + * Calculate checksum for the partition + */ + Status = CalcPartitionChecksum(StartAddr, Length, &CalcChecksum[0]); + if(Status != XST_SUCCESS) { + return XST_FAILURE; + } + + fsbl_printf(DEBUG_INFO, "Calculated checksum\r\n"); + + for (Index = 0; Index < MD5_CHECKSUM_SIZE; Index++) { + fsbl_printf(DEBUG_INFO, "0x%0x ",CalcChecksum[Index]); + } + + fsbl_printf(DEBUG_INFO, "\r\n"); + + /* + * Compare actual checksum with the calculated checksum + */ + for (Index = 0; Index < MD5_CHECKSUM_SIZE; Index++) { + if(Checksum[Index] != CalcChecksum[Index]) { + fsbl_printf(DEBUG_GENERAL, "Error: " + "Partition DataChecksum 0x%0x!= 0x%0x\r\n", + Checksum[Index], CalcChecksum[Index]); + return XST_FAILURE; + } + } + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function gets partition checksum from flash +* +* @param Check sum offset +* @param Checksum pointer +* @return +* - XST_SUCCESS if checksum read success +* - XST_FAILURE if unable get checksum +* +* @note None +* +*******************************************************************************/ +u32 GetPartitionChecksum(u32 ChecksumOffset, u8 *Checksum) +{ + u32 Status; + + Status = MoveImage(ChecksumOffset, (u32)Checksum, MD5_CHECKSUM_SIZE); + if(Status != XST_SUCCESS) { + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function calculates the checksum preset in image +* +* @param Start address +* @param Length of the data +* @param Checksum pointer +* +* @return +* - XST_SUCCESS if Checksum calculate successful +* - XST_FAILURE if Checksum calculate failed +* +* @note None +* +*******************************************************************************/ +u32 CalcPartitionChecksum(u32 SourceAddr, u32 DataLength, u8 *Checksum) +{ + /* + * Calculate checksum using MD5 algorithm + */ + md5((u8*)SourceAddr, DataLength, Checksum, 0 ); + + return XST_SUCCESS; +} + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/image_mover.h b/quad/xsdk_workspace/zybo_fsbl/src/image_mover.h new file mode 100644 index 0000000000000000000000000000000000000000..e74d0bebc73914649fe4215781373086dfe4059c --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/image_mover.h @@ -0,0 +1,166 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file image_mover.h +* +* This file contains the interface for moving the image from FLASH to OCM + +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a jz 03/04/11 Initial release +* 2.00a jz 06/04/11 partition header expands to 12 words +* 5.00a kc 07/30/13 Added defines for image header information +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___IMAGE_MOVER_H___ +#define ___IMAGE_MOVER_H___ + + +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ +#include "fsbl.h" + +/************************** Constant Definitions *****************************/ +#define PARTITION_NUMBER_SHIFT 24 +#define MAX_PARTITION_NUMBER (0xE) + +/* Boot Image Header defines */ +#define IMAGE_HDR_OFFSET 0x098 /* Start of image header table */ +#define IMAGE_PHDR_OFFSET 0x09C /* Start of partition headers */ +#define IMAGE_HEADER_SIZE (64) +#define IMAGE_HEADER_TABLE_SIZE (64) +#define TOTAL_PARTITION_HEADER_SIZE (MAX_PARTITION_NUMBER * IMAGE_HEADER_SIZE) +#define TOTAL_IMAGE_HEADER_SIZE (MAX_PARTITION_NUMBER * IMAGE_HEADER_SIZE) +#define TOTAL_HEADER_SIZE (IMAGE_HEADER_TABLE_SIZE + \ + TOTAL_IMAGE_HEADER_SIZE + \ + TOTAL_PARTITION_HEADER_SIZE + 64) + +/* Partition Header defines */ +#define PARTITION_IMAGE_WORD_LEN_OFFSET 0x00 /* Word length of image */ +#define PARTITION_DATA_WORD_LEN_OFFSET 0x04 /* Word length of data */ +#define PARTITION_WORD_LEN_OFFSET 0x08 /* Word length of partition */ +#define PARTITION_LOAD_ADDRESS_OFFSET 0x0C /* Load addr in DDR */ +#define PARTITION_EXEC_ADDRESS_OFFSET 0x10 /* Addr to start executing */ +#define PARTITION_ADDR_OFFSET 0x14 /* Partition word offset */ +#define PARTITION_ATTRIBUTE_OFFSET 0x18 /* Partition type */ +#define PARTITION_HDR_CHECKSUM_OFFSET 0x3C /* Header Checksum offset */ +#define PARTITION_HDR_CHECKSUM_WORD_COUNT 0xF /* Checksum word count */ +#define PARTITION_HDR_WORD_COUNT 0x10 /* Header word len */ +#define PARTITION_HDR_TOTAL_LEN 0x40 /* One partition hdr length*/ + +/* Attribute word defines */ +#define ATTRIBUTE_IMAGE_TYPE_MASK 0xF0 /* Destination Device type */ +#define ATTRIBUTE_PS_IMAGE_MASK 0x10 /* Code partition */ +#define ATTRIBUTE_PL_IMAGE_MASK 0x20 /* Bit stream partition */ +#define ATTRIBUTE_CHECKSUM_TYPE_MASK 0x7000 /* Checksum Type */ +#define ATTRIBUTE_RSA_PRESENT_MASK 0x8000 /* RSA Signature Present */ + + +/**************************** Type Definitions *******************************/ +typedef u32 (*ImageMoverType)( u32 SourceAddress, + u32 DestinationAddress, + u32 LengthBytes); + +typedef struct StructPartHeader { + u32 ImageWordLen; /* 0x0 */ + u32 DataWordLen; /* 0x4 */ + u32 PartitionWordLen; /* 0x8 */ + u32 LoadAddr; /* 0xC */ + u32 ExecAddr; /* 0x10 */ + u32 PartitionStart; /* 0x14 */ + u32 PartitionAttr; /* 0x18 */ + u32 SectionCount; /* 0x1C */ + u32 CheckSumOffset; /* 0x20 */ + u32 Pads1[1]; + u32 ACOffset; /* 0x28 */ + u32 Pads2[4]; + u32 CheckSum; /* 0x3C */ +}PartHeader; + +struct HeaderArray { + u32 Fields[16]; +}; + + +/***************** Macros (Inline Functions) Definitions *********************/ +#define MoverIn32 Xil_In32 +#define MoverOut32 Xil_Out32 + +/************************** Function Prototypes ******************************/ +u32 LoadBootImage(void); +u32 GetPartitionHeaderInfo(u32 ImageBaseAddress); +u32 PartitionMove(u32 ImageBaseAddress, PartHeader *Header); +u32 ValidatePartitionHeaderChecksum(struct HeaderArray *H); +u32 GetPartitionHeaderStartAddr(u32 ImageAddress, u32 *Offset); +u32 GetImageHeaderAndSignature(u32 ImageAddress, u32 *Offset); +u32 GetFsblLength(u32 ImageAddress, u32 *FsblLength); +u32 LoadPartitionsHeaderInfo(u32 PartHeaderOffset, PartHeader *Header); +u32 IsEmptyHeader(struct HeaderArray *H); +u32 IsLastPartition(struct HeaderArray *H); +void HeaderDump(PartHeader *Header); +u32 GetPartitionCount(PartHeader *Header); +u32 ValidateHeader(PartHeader *Header); +u32 DecryptPartition(u32 StartAddr, u32 DataLength, u32 ImageLength); + +/************************** Variable Definitions *****************************/ + +#ifdef __cplusplus +} +#endif + + +#endif /* ___IMAGE_MOVER_H___ */ + + + + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/integer.h b/quad/xsdk_workspace/zybo_fsbl/src/integer.h new file mode 100644 index 0000000000000000000000000000000000000000..75f5709a3873ba02f6928f1fc612d2f62d7aa028 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/integer.h @@ -0,0 +1,36 @@ +/*-------------------------------------------*/ +/* Integer type definitions for FatFs module */ +/*-------------------------------------------*/ + +#ifndef _INTEGER +#define _INTEGER + +#ifdef _WIN32 /* FatFs development platform */ + +#include <tchar.h> + +#else /* Embedded platform */ + +/* These types must be 16-bit, 32-bit or larger integer */ +typedef int INT; +typedef unsigned int UINT; + +/* These types must be 8-bit integer */ +typedef char CHAR; +typedef unsigned char UCHAR; +typedef unsigned char BYTE; + +/* These types must be 16-bit integer */ +typedef short SHORT; +typedef unsigned short USHORT; +typedef unsigned short WORD; +typedef unsigned short WCHAR; + +/* These types must be 32-bit integer */ +typedef long LONG; +typedef unsigned long ULONG; +typedef unsigned long DWORD; + +#endif + +#endif diff --git a/quad/xsdk_workspace/zybo_fsbl/src/librsa.a b/quad/xsdk_workspace/zybo_fsbl/src/librsa.a new file mode 100644 index 0000000000000000000000000000000000000000..cdf35a3f339c3d48fe2c67eea6e13806618178a2 Binary files /dev/null and b/quad/xsdk_workspace/zybo_fsbl/src/librsa.a differ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/lscript.ld b/quad/xsdk_workspace/zybo_fsbl/src/lscript.ld new file mode 100644 index 0000000000000000000000000000000000000000..d86df11b1e9cc1e5f3a74586509fdd18dfbda07b --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/lscript.ld @@ -0,0 +1,287 @@ +/*******************************************************************/ +/* */ +/* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved */ +/* */ +/* Description : FSBL Linker Script */ +/* */ +/*******************************************************************/ + +_STACK_SIZE = DEFINED(_STACK_SIZE) ? _STACK_SIZE : 0x6000; +_HEAP_SIZE = DEFINED(_HEAP_SIZE) ? _HEAP_SIZE : 0x2000; + +_RSA_AC_SIZE = DEFINED(_RSA_AC_SIZE) ? _RSA_AC_SIZE : 0x1000; + +_ABORT_STACK_SIZE = DEFINED(_ABORT_STACK_SIZE) ? _ABORT_STACK_SIZE : 1024; +_SUPERVISOR_STACK_SIZE = DEFINED(_SUPERVISOR_STACK_SIZE) ? _SUPERVISOR_STACK_SIZE : 2048; +_FIQ_STACK_SIZE = DEFINED(_FIQ_STACK_SIZE) ? _FIQ_STACK_SIZE : 1024; +_UNDEF_STACK_SIZE = DEFINED(_UNDEF_STACK_SIZE) ? _UNDEF_STACK_SIZE : 1024; + +/* Define Memories in the system */ + +MEMORY +{ + ps7_ram_0_S_AXI_BASEADDR : ORIGIN = 0x00000000, LENGTH = 0x00030000 + ps7_ram_1_S_AXI_BASEADDR : ORIGIN = 0xFFFF0000, LENGTH = 0x0000FE00 +} + +/* Specify the default entry point to the program */ + +ENTRY(_vector_table) + + +SECTIONS +{ +.text : { + *(.vectors) + *(.boot) + *(.text) + *(.text.*) + *(.gnu.linkonce.t.*) + *(.plt) + *(.gnu_warning) + *(.gcc_execpt_table) + *(.glue_7) + *(.glue_7t) + *(.vfp11_veneer) + *(.ARM.extab) + *(.gnu.linkonce.armextab.*) +} > ps7_ram_0_S_AXI_BASEADDR + +.init : { + KEEP (*(.init)) +} > ps7_ram_0_S_AXI_BASEADDR + +.fini : { + KEEP (*(.fini)) +} > ps7_ram_0_S_AXI_BASEADDR + +.rodata : { + __rodata_start = .; + *(.rodata) + *(.rodata.*) + *(.gnu.linkonce.r.*) + __rodata_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.rodata1 : { + __rodata1_start = .; + *(.rodata1) + *(.rodata1.*) + __rodata1_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.sdata2 : { + __sdata2_start = .; + *(.sdata2) + *(.sdata2.*) + *(.gnu.linkonce.s2.*) + __sdata2_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.sbss2 : { + __sbss2_start = .; + *(.sbss2) + *(.sbss2.*) + *(.gnu.linkonce.sb2.*) + __sbss2_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.data : { + __data_start = .; + *(.data) + *(.data.*) + *(.gnu.linkonce.d.*) + *(.jcr) + *(.got) + *(.got.plt) + __data_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.data1 : { + __data1_start = .; + *(.data1) + *(.data1.*) + __data1_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.got : { + *(.got) +} > ps7_ram_0_S_AXI_BASEADDR + +.ctors : { + __CTOR_LIST__ = .; + ___CTORS_LIST___ = .; + KEEP (*crtbegin.o(.ctors)) + KEEP (*(EXCLUDE_FILE(*crtend.o) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*(.ctors)) + __CTOR_END__ = .; + ___CTORS_END___ = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.dtors : { + __DTOR_LIST__ = .; + ___DTORS_LIST___ = .; + KEEP (*crtbegin.o(.dtors)) + KEEP (*(EXCLUDE_FILE(*crtend.o) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*(.dtors)) + __DTOR_END__ = .; + ___DTORS_END___ = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.fixup : { + __fixup_start = .; + *(.fixup) + __fixup_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.eh_frame : { + *(.eh_frame) +} > ps7_ram_0_S_AXI_BASEADDR + +.eh_framehdr : { + __eh_framehdr_start = .; + *(.eh_framehdr) + __eh_framehdr_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.gcc_except_table : { + *(.gcc_except_table) +} > ps7_ram_0_S_AXI_BASEADDR + +.mmu_tbl ALIGN(0x4000): { + __mmu_tbl_start = .; + *(.mmu_tbl) + __mmu_tbl_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.ARM.exidx : { + __exidx_start = .; + *(.ARM.exidx*) + *(.gnu.linkonce.armexidix.*.*) + __exidx_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.preinit_array : { + __preinit_array_start = .; + KEEP (*(SORT(.preinit_array.*))) + KEEP (*(.preinit_array)) + __preinit_array_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.init_array : { + __init_array_start = .; + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + __init_array_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.fini_array : { + __fini_array_start = .; + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array)) + __fini_array_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.rsa_ac : { + . = ALIGN(64); + __rsa_ac_start = .; + . += _RSA_AC_SIZE; + __rsa_ac_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.ARM.attributes : { + __ARM.attributes_start = .; + *(.ARM.attributes) + __ARM.attributes_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.sdata : { + __sdata_start = .; + *(.sdata) + *(.sdata.*) + *(.gnu.linkonce.s.*) + __sdata_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.sbss (NOLOAD) : { + __sbss_start = .; + *(.sbss) + *(.sbss.*) + *(.gnu.linkonce.sb.*) + __sbss_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.tdata : { + __tdata_start = .; + *(.tdata) + *(.tdata.*) + *(.gnu.linkonce.td.*) + __tdata_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.tbss : { + __tbss_start = .; + *(.tbss) + *(.tbss.*) + *(.gnu.linkonce.tb.*) + __tbss_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.bss (NOLOAD) : { + __bss_start = .; + *(.bss) + *(.bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + __bss_end = .; +} > ps7_ram_0_S_AXI_BASEADDR + +_SDA_BASE_ = __sdata_start + ((__sbss_end - __sdata_start) / 2 ); + +_SDA2_BASE_ = __sdata2_start + ((__sbss2_end - __sdata2_start) / 2 ); + +/* Generate Stack and Heap definitions */ + +.heap (NOLOAD) : { + . = ALIGN(16); + _heap = .; + HeapBase = .; + _heap_start = .; + . += _HEAP_SIZE; + _heap_end = .; + HeapLimit = .; +} > ps7_ram_0_S_AXI_BASEADDR + +.stack (NOLOAD) : { + . = ALIGN(16); + _stack_end = .; + . += _STACK_SIZE; + _stack = .; + __stack = _stack; + . = ALIGN(16); + _irq_stack_end = .; + . += _STACK_SIZE; + __irq_stack = .; + _supervisor_stack_end = .; + . += _SUPERVISOR_STACK_SIZE; + . = ALIGN(16); + __supervisor_stack = .; + _abort_stack_end = .; + . += _ABORT_STACK_SIZE; + . = ALIGN(16); + __abort_stack = .; + _fiq_stack_end = .; + . += _FIQ_STACK_SIZE; + . = ALIGN(16); + __fiq_stack = .; + _undef_stack_end = .; + . += _UNDEF_STACK_SIZE; + . = ALIGN(16); + __undef_stack = .; +} > ps7_ram_1_S_AXI_BASEADDR + +_end = .; +} + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/main.c b/quad/xsdk_workspace/zybo_fsbl/src/main.c new file mode 100644 index 0000000000000000000000000000000000000000..aff88aebf52fe41d711a91aee3bf4785050bb1ba --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/main.c @@ -0,0 +1,1516 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file main.c +* +* The main file for the First Stage Boot Loader (FSBL). +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a jz 06/04/11 Initial release +* 2.00a mb 25/05/12 standalone based FSBL +* 3.00a np/mb 08/03/12 Added call to FSBL user hook - before handoff. +* DDR ECC initialization added +* fsbl print with verbose added +* Performance measurement added +* Flushed the UART Tx buffer +* Added the performance time for ECC DDR init +* Added clearing of ECC Error Code +* Added the watchdog timer value +* 4.00a sgd 02/28/13 Code Cleanup +* Fix for CR#681014 - ECC init in FSBL should not +* call fabric_init() +* Fix for CR#689077 - FSBL hangs at Handoff clearing the +* TX UART buffer when using UART0 +* instead of UART1 +* Fix for CR#694038 - FSBL debug logs always prints 14.3 +* as the Revision number - this is +* incorrect +* Fix for CR#694039 - FSBL prints "unsupported silicon +* version for v3.0" 3.0 Silicon +* Fix for CR#699475 - FSBL functionality is broken and +* its not able to boot in QSPI/NAND +* bootmode +* Removed DDR initialization check +* Removed DDR ECC initialization code +* Modified hand off address check to 1MB +* Added RSA authentication support +* Watchdog disabled for AES E-Fuse encryption +* 5.00a sgd 05/17/13 Fallback support for E-Fuse encryption +* Fix for CR#708728 - Issues seen while making HP +* interconnect 32 bit wide +* 6.00a kc 07/30/13 Fix for CR#708316 - PS7_init.tcl file should have +* Error mechanism for all mask_poll +* Fix for CR#691150 - ps7_init does not check for +* peripheral initialization failures +* or timeout on polls +* Fix for CR#724165 - Partition Header used by FSBL is +* not authenticated +* Fix for CR#724166 - FSBL doesn’t use PPK authenticated +* by Boot ROM for authenticating +* the Partition images +* Fix for CR#722979 - Provide customer-friendly +* changelogs in FSBL +* Fix for CR#732865 - Backward compatibility for ps7_init +* function +* </pre> +* +* @note +* FSBL runs from OCM, Based on the boot mode selected, FSBL will copy +* the partitions from the flash device. If the partition is bitstream then +* the bitstream is programmed in the Fabric and for an partition that is +* an application , FSBL will copy the application into DDR and does a +* handoff.The application should not be starting at the OCM address, +* FSBL does not remap the DDR. Application should use DDR starting from 1MB +* +* FSBL can be stitched along with bitstream and application using bootgen +* +* Refer to fsbl.h file for details on the compilation flags supported in FSBL +* +******************************************************************************/ + +/***************************** Include Files *********************************/ + +#include "fsbl.h" +#include "qspi.h" +#include "nand.h" +#include "nor.h" +#include "sd.h" +#include "pcap.h" +#include "image_mover.h" +#include "xparameters.h" +#include "xil_cache.h" +#include "xil_exception.h" +#include "xstatus.h" +#include "fsbl_hooks.h" +#include "xtime_l.h" + +#ifdef XPAR_XWDTPS_0_BASEADDR +#include "xwdtps.h" +#endif + +#ifdef STDOUT_BASEADDRESS +#include "xuartps_hw.h" +#endif + +/************************** Constant Definitions *****************************/ + +#ifdef XPAR_XWDTPS_0_BASEADDR +#define WDT_DEVICE_ID XPAR_XWDTPS_0_DEVICE_ID +#define WDT_EXPIRE_TIME 100 +#define WDT_CRV_SHIFT 12 +#endif + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +#ifdef XPAR_XWDTPS_0_BASEADDR +XWdtPs Watchdog; /* Instance of WatchDog Timer */ +#endif +/************************** Function Prototypes ******************************/ +extern int ps7_init(); +extern char* getPS7MessageInfo(unsigned key); +#ifdef PS7_POST_CONFIG +extern int ps7_post_config(); +#endif +#ifdef PEEP_CODE +extern void init_ddr(void); +#endif + +static void Update_MultiBootRegister(void); +/* Exception handlers */ +static void RegisterHandlers(void); +static void Undef_Handler (void); +static void SVC_Handler (void); +static void PreFetch_Abort_Handler (void); +static void Data_Abort_Handler (void); +static void IRQ_Handler (void); +static void FIQ_Handler (void); + + +#ifdef XPAR_XWDTPS_0_BASEADDR +int InitWatchDog(void); +u32 ConvertTime_WdtCounter(u32 seconds); +void CheckWDTReset(void); +#endif + +u32 NextValidImageCheck(void); + +u32 DDRInitCheck(void); + +/************************** Variable Definitions *****************************/ +/* + * Base Address for the Read Functionality for Image Processing + */ +u32 FlashReadBaseAddress = 0; +/* + * Silicon Version + */ +u32 Silicon_Version; + +/* + * Boot Device flag + */ +u8 LinearBootDeviceFlag; + +u32 PcapCtrlRegVal; + +u8 SystemInitFlag; + +extern ImageMoverType MoveImage; +extern XDcfg *DcfgInstPtr; +extern u8 BitstreamFlag; +#ifdef XPAR_PS7_QSPI_LINEAR_0_S_AXI_BASEADDR +extern u32 QspiFlashSize; +#endif +/*****************************************************************************/ +/** +* +* This is the main function for the FSBL ROM code. +* +* +* @param None. +* +* @return +* - XST_SUCCESS to indicate success +* - XST_FAILURE.to indicate failure +* +* @note +* +****************************************************************************/ +int main(void) +{ + u32 BootModeRegister = 0; + u32 HandoffAddress = 0; + u32 Status = XST_SUCCESS; + +#ifdef PEEP_CODE + /* + * PEEP DDR initialization + */ + init_ddr(); +#else + /* + * PCW initialization for MIO,PLL,CLK and DDR + */ + Status = ps7_init(); + if (Status != FSBL_PS7_INIT_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"PS7_INIT_FAIL : %s\r\n", + getPS7MessageInfo(Status)); + OutputStatus(PS7_INIT_FAIL); + /* + * Calling FsblHookFallback instead of Fallback + * since, devcfg driver is not yet initialized + */ + FsblHookFallback(); + } +#endif + + /* + * Unlock SLCR for SLCR register write + */ + SlcrUnlock(); + + /* If Performance measurement is required + * then read the Global Timer value , Please note that the + * time taken for mio, clock and ddr initialisation + * done in the ps7_init function is not accounted in the FSBL + * + */ +#ifdef FSBL_PERF + XTime tCur = 0; + FsblGetGlobalTime(tCur); +#endif + + /* + * Flush the Caches + */ + Xil_DCacheFlush(); + + /* + * Disable Data Cache + */ + Xil_DCacheDisable(); + + /* + * Register the Exception handlers + */ + RegisterHandlers(); + + /* + * Print the FSBL Banner + */ + fsbl_printf(DEBUG_GENERAL,"\n\rXilinx First Stage Boot Loader \n\r"); + fsbl_printf(DEBUG_GENERAL,"Release %d.%d/%d.%d %s-%s\r\n", + SDK_RELEASE_VER, SDK_SUB_VER, + SDK_RELEASE_YEAR, SDK_RELEASE_QUARTER, + __DATE__,__TIME__); + +#ifdef XPAR_PS7_DDR_0_S_AXI_BASEADDR + + /* + * DDR Read/write test + */ + Status = DDRInitCheck(); + if (Status == XST_FAILURE) { + fsbl_printf(DEBUG_GENERAL,"DDR_INIT_FAIL \r\n"); + /* Error Handling here */ + OutputStatus(DDR_INIT_FAIL); + /* + * Calling FsblHookFallback instead of Fallback + * since, devcfg driver is not yet initialized + */ + FsblHookFallback(); + } + + + /* + * PCAP initialization + */ + Status = InitPcap(); + if (Status == XST_FAILURE) { + fsbl_printf(DEBUG_GENERAL,"PCAP_INIT_FAIL \n\r"); + OutputStatus(PCAP_INIT_FAIL); + /* + * Calling FsblHookFallback instead of Fallback + * since, devcfg driver is not yet initialized + */ + FsblHookFallback(); + } + + fsbl_printf(DEBUG_INFO,"Devcfg driver initialized \r\n"); + + /* + * Get the Silicon Version + */ + GetSiliconVersion(); + +#ifdef XPAR_XWDTPS_0_BASEADDR + /* + * Check if WDT Reset has occurred or not + */ + CheckWDTReset(); + + /* + * Initialize the Watchdog Timer so that it is ready to use + */ + Status = InitWatchDog(); + if (Status == XST_FAILURE) { + fsbl_printf(DEBUG_GENERAL,"WATCHDOG_INIT_FAIL \n\r"); + OutputStatus(WDT_INIT_FAIL); + FsblFallback(); + } + fsbl_printf(DEBUG_INFO,"Watchdog driver initialized \r\n"); +#endif + + /* + * Get PCAP controller settings + */ + PcapCtrlRegVal = XDcfg_GetControlRegister(DcfgInstPtr); + + /* + * Check for AES source key + */ + if (PcapCtrlRegVal & PCAP_CTRL_PCFG_AES_FUSE_EFUSE_MASK) { + /* + * For E-Fuse AES encryption Watch dog Timer disabled and + * User not allowed to do system reset + */ +#ifdef XPAR_XWDTPS_0_BASEADDR + fsbl_printf(DEBUG_INFO,"Watchdog Timer Disabled\r\n"); + XWdtPs_Stop(&Watchdog); +#endif + fsbl_printf(DEBUG_INFO,"User not allowed to do " + "any system resets\r\n"); + } + + /* + * Store FSBL run state in Reboot Status Register + */ + MarkFSBLIn(); + + /* + * Read bootmode register + */ + BootModeRegister = Xil_In32(BOOT_MODE_REG); + BootModeRegister &= BOOT_MODES_MASK; + + /* + * QSPI BOOT MODE + */ +#ifdef XPAR_PS7_QSPI_LINEAR_0_S_AXI_BASEADDR + +#ifdef MMC_SUPPORT + /* + * To support MMC boot + * QSPI boot mode detection ignored + */ + if (BootModeRegister == QSPI_MODE) { + BootModeRegister = MMC_MODE; + } +#endif + + if (BootModeRegister == QSPI_MODE) { + fsbl_printf(DEBUG_GENERAL,"Boot mode is QSPI\n\r"); + InitQspi(); + MoveImage = QspiAccess; + fsbl_printf(DEBUG_INFO,"QSPI Init Done \r\n"); + } else +#endif + + /* + * NAND BOOT MODE + */ +#ifdef XPAR_PS7_NAND_0_BASEADDR + if (BootModeRegister == NAND_FLASH_MODE) { + /* + * Boot ROM always initialize the nand at lower speed + * This is the chance to put it to an optimum speed for your nand + * device + */ + fsbl_printf(DEBUG_GENERAL,"Boot mode is NAND\n"); + + Status = InitNand(); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"NAND_INIT_FAIL \r\n"); + /* + * Error Handling here + */ + OutputStatus(NAND_INIT_FAIL); + FsblFallback(); + } + MoveImage = NandAccess; + fsbl_printf(DEBUG_INFO,"NAND Init Done \r\n"); + } else +#endif + + /* + * NOR BOOT MODE + */ + if (BootModeRegister == NOR_FLASH_MODE) { + fsbl_printf(DEBUG_GENERAL,"Boot mode is NOR\n\r"); + /* + * Boot ROM always initialize the nor at lower speed + * This is the chance to put it to an optimum speed for your nor + * device + */ + InitNor(); + fsbl_printf(DEBUG_INFO,"NOR Init Done \r\n"); + MoveImage = NorAccess; + } else + + /* + * SD BOOT MODE + */ +#ifdef XPAR_PS7_SD_0_S_AXI_BASEADDR + + if (BootModeRegister == SD_MODE) { + fsbl_printf(DEBUG_GENERAL,"Boot mode is SD\r\n"); + + /* + * SD initialization returns file open error or success + */ + Status = InitSD("BOOT.BIN"); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"SD_INIT_FAIL\r\n"); + OutputStatus(SD_INIT_FAIL); + FsblFallback(); + } + MoveImage = SDAccess; + fsbl_printf(DEBUG_INFO,"SD Init Done \r\n"); + } else + + if (BootModeRegister == MMC_MODE) { + fsbl_printf(DEBUG_GENERAL,"Booting Device is MMC\r\n"); + + /* + * MMC initialization returns file open error or success + */ + Status = InitSD("BOOT.BIN"); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"MMC_INIT_FAIL\r\n"); + OutputStatus(SD_INIT_FAIL); + FsblFallback(); + } + MoveImage = SDAccess; + fsbl_printf(DEBUG_INFO,"MMC Init Done \r\n"); + } else + +#endif + + /* + * JTAG BOOT MODE + */ + if (BootModeRegister == JTAG_MODE) { + fsbl_printf(DEBUG_GENERAL,"Boot mode is JTAG\r\n"); + /* + * Stop the Watchdog before JTAG handoff + */ +#ifdef XPAR_XWDTPS_0_BASEADDR + XWdtPs_Stop(&Watchdog); +#endif + /* + * Clear our mark in reboot status register + */ + ClearFSBLIn(); + + /* + * SLCR lock + */ + SlcrLock(); + + FsblHandoffJtagExit(); + } else { + fsbl_printf(DEBUG_GENERAL,"ILLEGAL_BOOT_MODE \r\n"); + OutputStatus(ILLEGAL_BOOT_MODE); + /* + * fallback starts, no return + */ + FsblFallback(); + } + + fsbl_printf(DEBUG_INFO,"Flash Base Address: 0x%08x\r\n", FlashReadBaseAddress); + + /* + * Check for valid flash address + */ + if ((FlashReadBaseAddress != XPS_QSPI_LINEAR_BASEADDR) && + (FlashReadBaseAddress != XPS_NAND_BASEADDR) && + (FlashReadBaseAddress != XPS_NOR_BASEADDR) && + (FlashReadBaseAddress != XPS_SDIO0_BASEADDR)) { + fsbl_printf(DEBUG_GENERAL,"INVALID_FLASH_ADDRESS \r\n"); + OutputStatus(INVALID_FLASH_ADDRESS); + FsblFallback(); + } + + /* + * NOR and QSPI (parallel) are linear boot devices + */ + if ((FlashReadBaseAddress == XPS_NOR_BASEADDR)) { + fsbl_printf(DEBUG_INFO, "Linear Boot Device\r\n"); + LinearBootDeviceFlag = 1; + } + +#ifdef XPAR_XWDTPS_0_BASEADDR + /* + * Prevent WDT reset + */ + XWdtPs_RestartWdt(&Watchdog); +#endif + + /* + * This used only in case of E-Fuse encryption + * For image search + */ + SystemInitFlag = 1; + + /* + * Load boot image + */ + HandoffAddress = LoadBootImage(); + + fsbl_printf(DEBUG_INFO,"Handoff Address: 0x%08x\r\n",HandoffAddress); + + /* + * For Performance measurement + */ +#ifdef FSBL_PERF + XTime tEnd = 0; + fsbl_printf(DEBUG_GENERAL,"Total Execution time is "); + FsblMeasurePerfTime(tCur,tEnd); +#endif + + /* + * FSBL handoff to valid handoff address or + * exit in JTAG + */ + FsblHandoff(HandoffAddress); + +#else + OutputStatus(NO_DDR); + FsblFallback(); +#endif + + return Status; +} + +/******************************************************************************/ +/** +* +* This function reset the CPU and goes for Boot ROM fallback handling +* +* @param None +* +* @return None +* +* @note None +* +****************************************************************************/ +void FsblFallback(void) +{ + u32 RebootStatusReg; + u32 Status; + u32 HandoffAddr; + u32 BootModeRegister; + + /* + * Read bootmode register + */ + BootModeRegister = Xil_In32(BOOT_MODE_REG); + BootModeRegister &= BOOT_MODES_MASK; + + /* + * Fallback support check + */ + if (!((BootModeRegister == QSPI_MODE) || + (BootModeRegister == NAND_FLASH_MODE) || + (BootModeRegister == NOR_FLASH_MODE))) { + fsbl_printf(DEBUG_INFO,"\r\n" + "This Boot Mode Doesn't Support Fallback\r\n"); + ClearFSBLIn(); + FsblHookFallback(); + } + + /* + * update the Multiboot Register for Golden search hunt + */ + Update_MultiBootRegister(); + + /* + * Notify Boot ROM something is wrong + */ + RebootStatusReg = Xil_In32(REBOOT_STATUS_REG); + + /* + * Set the FSBL Fail mask + */ + Xil_Out32(REBOOT_STATUS_REG, RebootStatusReg | FSBL_FAIL_MASK); + + /* + * Barrier for synchronization + */ + asm( + "dsb\n\t" + "isb" + ); + + /* + * Check for AES source key + */ + if (PcapCtrlRegVal & PCAP_CTRL_PCFG_AES_FUSE_EFUSE_MASK) { + /* + * Next valid image search can happen only + * when system initialization done + */ + if (SystemInitFlag == 1) { + /* + * Clean the Fabric + */ + FabricInit(); + + /* + * Search for next valid image + */ + Status = NextValidImageCheck(); + if(Status != XST_SUCCESS){ + fsbl_printf(DEBUG_INFO,"\r\nNo Image Found\r\n"); + ClearFSBLIn(); + FsblHookFallback(); + } + + /* + * Load next valid image + */ + HandoffAddr = LoadBootImage(); + + /* + * Handoff to next image + */ + FsblHandoff(HandoffAddr); + } else { + fsbl_printf(DEBUG_INFO,"System Initialization Failed\r\n"); + fsbl_printf(DEBUG_INFO,"\r\nNo Image Search\r\n"); + ClearFSBLIn(); + FsblHookFallback(); + } + } + + /* + * Reset PS, so Boot ROM will restart + */ + Xil_Out32(PS_RST_CTRL_REG, PS_RST_MASK); +} + + +/******************************************************************************/ +/** +* +* This function hands the A9/PS to the loaded user code. +* +* @param none +* +* @return none +* +* @note This function does not return. +* +****************************************************************************/ +void FsblHandoff(u32 FsblStartAddr) +{ + u32 Status; + + /* + * Enable level shifter + */ + if(BitstreamFlag) { + /* + * FSBL will not enable the level shifters for a NON PS instantiated + * Bitstream + * CR# 671028 + * This flag can be set during compilation for a NON PS instantiated + * bitstream + */ +#ifndef NON_PS_INSTANTIATED_BITSTREAM +#ifdef PS7_POST_CONFIG + ps7_post_config(); + /* + * Unlock SLCR for SLCR register write + */ + SlcrUnlock(); +#else + /* + * Set Level Shifters DT618760 + */ + Xil_Out32(PS_LVL_SHFTR_EN, LVL_PL_PS); + fsbl_printf(DEBUG_INFO,"Enabling Level Shifters PL to PS " + "Address = 0x%x Value = 0x%x \n\r", + PS_LVL_SHFTR_EN, Xil_In32(PS_LVL_SHFTR_EN)); + + /* + * Enable AXI interface + */ + Xil_Out32(FPGA_RESET_REG, 0); + fsbl_printf(DEBUG_INFO,"AXI Interface enabled \n\r"); + fsbl_printf(DEBUG_INFO, "FPGA Reset Register " + "Address = 0x%x , Value = 0x%x \r\n", + FPGA_RESET_REG ,Xil_In32(FPGA_RESET_REG)); +#endif +#endif + } + + /* + * FSBL user hook call before handoff to the application + */ + Status = FsblHookBeforeHandoff(); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"FSBL_HANDOFF_HOOK_FAIL\r\n"); + OutputStatus(FSBL_HANDOFF_HOOK_FAIL); + FsblFallback(); + } + +#ifdef XPAR_XWDTPS_0_BASEADDR + XWdtPs_Stop(&Watchdog); +#endif + + /* + * Clear our mark in reboot status register + */ + ClearFSBLIn(); + + if(FsblStartAddr == 0) { + /* + * SLCR lock + */ + SlcrLock(); + + fsbl_printf(DEBUG_INFO,"No Execution Address JTAG handoff \r\n"); + FsblHandoffJtagExit(); + } else { + fsbl_printf(DEBUG_GENERAL,"SUCCESSFUL_HANDOFF\r\n"); + OutputStatus(SUCCESSFUL_HANDOFF); + FsblHandoffExit(FsblStartAddr); + } + + OutputStatus(ILLEGAL_RETURN); + + FsblFallback(); +} + +/******************************************************************************/ +/** +* +* This function outputs the status for the provided State in the boot process. +* +* @param State is where in the boot process the output is desired. +* +* @return None. +* +* @note None. +* +****************************************************************************/ +void OutputStatus(u32 State) +{ +#ifdef STDOUT_BASEADDRESS + u32 UartReg = 0; + + fsbl_printf(DEBUG_GENERAL,"FSBL Status = 0x%.4x\r\n", State); + /* + * The TX buffer needs to be flushed out + * If this is not done some of the prints will not appear on the + * serial output + */ + UartReg = Xil_In32(STDOUT_BASEADDRESS + XUARTPS_SR_OFFSET); + while ((UartReg & XUARTPS_SR_TXEMPTY) != XUARTPS_SR_TXEMPTY) { + UartReg = Xil_In32(STDOUT_BASEADDRESS + XUARTPS_SR_OFFSET); + } +#endif +} + +/******************************************************************************/ +/** +* +* This function handles the error and lockdown processing and outputs the status +* for the provided State in the boot process. +* +* This function is called upon exceptions. +* +* @param State - where in the boot process the error occured. +* +* @return None. +* +* @note This function does not return, the PS block is reset +* +****************************************************************************/ +void ErrorLockdown(u32 State) +{ + /* + * Store the error status + */ + OutputStatus(State); + + /* + * Fall back + */ + FsblFallback(); +} + +/******************************************************************************/ +/** +* +* This function copies a memory region to another memory region +* +* @param s1 is starting address for destination +* @param s2 is starting address for the source +* @param n is the number of bytes to copy +* +* @return Starting address for destination +* +****************************************************************************/ +void *(memcpy_rom)(void * s1, const void * s2, u32 n) +{ + char *dst = (char *)s1; + const char *src = (char *)s2; + + /* + * Loop and copy + */ + while (n-- != 0) + *dst++ = *src++; + return s1; +} +/******************************************************************************/ +/** +* +* This function copies a string to another, the source string must be null- +* terminated. +* +* @param Dest is starting address for the destination string +* @param Src is starting address for the source string +* +* @return Starting address for the destination string +* +****************************************************************************/ +char *strcpy_rom(char *Dest, const char *Src) +{ + unsigned i; + for (i=0; Src[i] != '\0'; ++i) + Dest[i] = Src[i]; + Dest[i] = '\0'; + return Dest; +} + + +/******************************************************************************/ +/** +* +* This function sets FSBL is running mask in reboot status register +* +* @param None. +* +* @return None. +* +* @note None. +* +****************************************************************************/ +void MarkFSBLIn(void) +{ + Xil_Out32(REBOOT_STATUS_REG, + Xil_In32(REBOOT_STATUS_REG) | FSBL_IN_MASK); +} + + +/******************************************************************************/ +/** +* +* This function clears FSBL is running mask in reboot status register +* +* @param None. +* +* @return None. +* +* @note None. +* +****************************************************************************/ +void ClearFSBLIn(void) +{ + Xil_Out32(REBOOT_STATUS_REG, + (Xil_In32(REBOOT_STATUS_REG)) & ~(FSBL_FAIL_MASK)); +} + +/******************************************************************************/ +/** +* +* This function Registers the Exception Handlers +* +* @param None. +* +* @return None. +* +* @note None. +* +****************************************************************************/ +static void RegisterHandlers(void) +{ + Xil_ExceptionInit(); + + /* + * Initialize the vector table. Register the stub Handler for each + * exception. + */ + Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_UNDEFINED_INT, + (Xil_ExceptionHandler)Undef_Handler, + (void *) 0); + Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_SWI_INT, + (Xil_ExceptionHandler)SVC_Handler, + (void *) 0); + Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_PREFETCH_ABORT_INT, + (Xil_ExceptionHandler)PreFetch_Abort_Handler, + (void *) 0); + Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_DATA_ABORT_INT, + (Xil_ExceptionHandler)Data_Abort_Handler, + (void *) 0); + Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_IRQ_INT, + (Xil_ExceptionHandler)IRQ_Handler,(void *) 0); + Xil_ExceptionRegisterHandler(XIL_EXCEPTION_ID_FIQ_INT, + (Xil_ExceptionHandler)FIQ_Handler,(void *) 0); + + Xil_ExceptionEnable(); + +} + +static void Undef_Handler (void) +{ + fsbl_printf(DEBUG_GENERAL,"UNDEFINED_HANDLER\r\n"); + ErrorLockdown (EXCEPTION_ID_UNDEFINED_INT); +} + +static void SVC_Handler (void) +{ + fsbl_printf(DEBUG_GENERAL,"SVC_HANDLER \r\n"); + ErrorLockdown (EXCEPTION_ID_SWI_INT); +} + +static void PreFetch_Abort_Handler (void) +{ + fsbl_printf(DEBUG_GENERAL,"PREFETCH_ABORT_HANDLER \r\n"); + ErrorLockdown (EXCEPTION_ID_PREFETCH_ABORT_INT); +} + +static void Data_Abort_Handler (void) +{ + fsbl_printf(DEBUG_GENERAL,"DATA_ABORT_HANDLER \r\n"); + ErrorLockdown (EXCEPTION_ID_DATA_ABORT_INT); +} + +static void IRQ_Handler (void) +{ + fsbl_printf(DEBUG_GENERAL,"IRQ_HANDLER \r\n"); + ErrorLockdown (EXCEPTION_ID_IRQ_INT); +} + +static void FIQ_Handler (void) +{ + fsbl_printf(DEBUG_GENERAL,"FIQ_HANDLER \r\n"); + ErrorLockdown (EXCEPTION_ID_FIQ_INT); +} + + +/******************************************************************************/ +/** +* +* This function Updates the Multi boot Register to enable golden image +* search for boot rom +* +* @param None +* +* @return +* return none +* +****************************************************************************/ +static void Update_MultiBootRegister(void) +{ + u32 MultiBootReg = 0; + + if (Silicon_Version != SILICON_VERSION_1) { + /* + * Read the mulitboot register + */ + MultiBootReg = XDcfg_ReadReg(DcfgInstPtr->Config.BaseAddr, + XDCFG_MULTIBOOT_ADDR_OFFSET); + + /* + * Incrementing multiboot register by one + */ + MultiBootReg++; + + XDcfg_WriteReg(DcfgInstPtr->Config.BaseAddr, + XDCFG_MULTIBOOT_ADDR_OFFSET, + MultiBootReg); + + fsbl_printf(DEBUG_INFO,"Updated MultiBootReg = 0x%08x\r\n", + MultiBootReg); + } +} + + +/****************************************************************************** +* +* This function reset the CPU and goes for Boot ROM fallback handling +* +* @param None +* +* @return None +* +* @note None +* +*******************************************************************************/ + +u32 GetResetReason(void) +{ + u32 Regval; + + /* We are using REBOOT_STATUS_REG, we have to use bits 23:16 */ + /* for storing the RESET_REASON register value*/ + Regval = ((Xil_In32(REBOOT_STATUS_REG) >> 16) & 0xFF); + + return Regval; +} + + +/****************************************************************************** +* +* This function Gets the ticks from the Global Timer +* +* @param Current time +* +* @return +* None +* +* @note None +* +*******************************************************************************/ +#ifdef FSBL_PERF +void FsblGetGlobalTime (XTime tCur) +{ + XTime_GetTime(&tCur); +} + + +/****************************************************************************** +* +* This function Measures the execution time +* +* @param Current time , End time +* +* @return +* None +* +* @note None +* +*******************************************************************************/ +void FsblMeasurePerfTime (XTime tCur, XTime tEnd) +{ + double tDiff = 0.0; + double tPerfSeconds; + XTime_GetTime(&tEnd); + tDiff = (double)tEnd - (double)tCur; + + /* + * Convert tPerf into Seconds + */ + tPerfSeconds = tDiff/COUNTS_PER_SECOND; + + /* + * Convert tPerf into Seconds + */ + tPerfSeconds = tDiff/COUNTS_PER_SECOND; + +#if defined(FSBL_DEBUG) || defined(FSBL_DEBUG_INFO) + printf("%f seconds \r\n",tPerfSeconds); +#endif + +} +#endif + +/****************************************************************************** +* +* This function initializes the Watchdog driver and starts the timer +* +* @param None +* +* @return +* - XST_SUCCESS if the Watchdog driver is initialized +* - XST_FAILURE if Watchdog driver initialization fails +* +* @note None +* +*******************************************************************************/ +#ifdef XPAR_XWDTPS_0_BASEADDR +int InitWatchDog(void) +{ + u32 Status = XST_SUCCESS; + XWdtPs_Config *ConfigPtr; /* Config structure of the WatchDog Timer */ + u32 CounterValue = 1; + + ConfigPtr = XWdtPs_LookupConfig(WDT_DEVICE_ID); + Status = XWdtPs_CfgInitialize(&Watchdog, + ConfigPtr, + ConfigPtr->BaseAddress); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"Watchdog Driver init Failed \n\r"); + return XST_FAILURE; + } + + /* + * Setting the divider value + */ + XWdtPs_SetControlValue(&Watchdog, + XWDTPS_CLK_PRESCALE, + XWDTPS_CCR_PSCALE_4096); + /* + * Convert time to Watchdog counter reset value + */ + CounterValue = ConvertTime_WdtCounter(WDT_EXPIRE_TIME); + + /* + * Set the Watchdog counter reset value + */ + XWdtPs_SetControlValue(&Watchdog, + XWDTPS_COUNTER_RESET, + CounterValue); + /* + * enable reset output, as we are only using this as a basic counter + */ + XWdtPs_EnableOutput(&Watchdog, XWDTPS_RESET_SIGNAL); + + /* + * Start the Watchdog timer + */ + XWdtPs_Start(&Watchdog); + + XWdtPs_RestartWdt(&Watchdog); + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function checks whether WDT reset has happened during FSBL run +* +* If WDT reset happened during FSBL run, then need to fallback +* +* @param None. +* +* @return +* None +* +* @note None +* +****************************************************************************/ +void CheckWDTReset(void) +{ + u32 ResetReason; + u32 RebootStatusRegister; + + RebootStatusRegister = Xil_In32(REBOOT_STATUS_REG); + + /* + * For 1.0 Silicon the reason for Reset is in the ResetReason Register + * Hence this register can be read to know the cause for previous reset + * that happened. + * Check if that reset is a Software WatchDog reset that happened + */ + if (Silicon_Version == SILICON_VERSION_1) { + ResetReason = Xil_In32(RESET_REASON_REG); + } else { + ResetReason = GetResetReason(); + } + /* + * If the FSBL_IN_MASK Has not been cleared, WDT happened + * before FSBL exits + */ + if ((ResetReason & RESET_REASON_SWDT) == RESET_REASON_SWDT ) { + if ((RebootStatusRegister & FSBL_FAIL_MASK) == FSBL_IN_MASK) { + /* + * Clear the SWDT Reset bit + */ + ResetReason &= ~RESET_REASON_SWDT; + if (Silicon_Version == SILICON_VERSION_1) { + /* + * for 1.0 Silicon we need to write + * 1 to the RESET REASON Clear register + */ + Xil_Out32(RESET_REASON_CLR, 1); + } else { + Xil_Out32(REBOOT_STATUS_REG, ResetReason); + } + + fsbl_printf(DEBUG_GENERAL,"WDT_RESET_OCCURED \n\r"); + } + } +} + + +/****************************************************************************** +* +* This function converts time into Watchdog counter value +* +* @param watchdog expire time in seconds +* +* @return +* Counter value for Watchdog +* +* @note None +* +*******************************************************************************/ +u32 ConvertTime_WdtCounter(u32 seconds) +{ + double time = 0.0; + double CounterValue; + u32 Crv = 0; + u32 Prescaler,PrescalerValue; + + Prescaler = XWdtPs_GetControlValue(&Watchdog, XWDTPS_CLK_PRESCALE); + + if (Prescaler == XWDTPS_CCR_PSCALE_0008) + PrescalerValue = 8; + if (Prescaler == XWDTPS_CCR_PSCALE_0064) + PrescalerValue = 64; + if (Prescaler == XWDTPS_CCR_PSCALE_4096) + PrescalerValue = 4096; + + time = (double)(PrescalerValue) / (double)XPAR_PS7_WDT_0_WDT_CLK_FREQ_HZ; + + CounterValue = seconds / time; + + Crv = (u32)CounterValue; + Crv >>= WDT_CRV_SHIFT; + + return Crv; +} + +#endif + + +/****************************************************************************** +* +* This function Gets the Silicon Version stores in global variable +* +* @param None +* +* @return None +* +* @note None +* +*******************************************************************************/ +void GetSiliconVersion(void) +{ + /* + * Get the silicon version + */ + Silicon_Version = XDcfg_GetPsVersion(DcfgInstPtr); + if(Silicon_Version == SILICON_VERSION_3_1) { + fsbl_printf(DEBUG_GENERAL,"Silicon Version 3.1\r\n"); + } else { + fsbl_printf(DEBUG_GENERAL,"Silicon Version %d.0\r\n", + Silicon_Version + 1); + } +} + + +/****************************************************************************** +* +* This function HeaderChecksum will calculates the header checksum and +* compares with checksum read from flash +* +* @param FlashOffsetAddress Flash offset address +* +* @return +* - XST_SUCCESS if ID matches +* - XST_FAILURE if ID mismatches +* +* @note None +* +*******************************************************************************/ +u32 HeaderChecksum(u32 FlashOffsetAddress){ + u32 Checksum = 0; + u32 Count; + u32 TempValue = 0; + + for (Count = 0; Count < IMAGE_HEADER_CHECKSUM_COUNT; Count++) { + /* + * Read the word from the header + */ + MoveImage(FlashOffsetAddress + IMAGE_WIDTH_CHECK_OFFSET + (Count*4), (u32)&TempValue, 4); + + /* + * Update checksum + */ + Checksum += TempValue; + } + + /* + * Invert checksum, last bit of error checking + */ + Checksum ^= 0xFFFFFFFF; + MoveImage(FlashOffsetAddress + IMAGE_CHECKSUM_OFFSET, (u32)&TempValue, 4); + + /* + * Validate the checksum + */ + if (TempValue != Checksum){ + fsbl_printf(DEBUG_INFO, "Checksum = %8.8x\r\n", Checksum); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/****************************************************************************** +* +* This function ImageCheckID will do check for XLNX pattern +* +* @param FlashOffsetAddress Flash offset address +* +* @return +* - XST_SUCCESS if ID matches +* - XST_FAILURE if ID mismatches +* +* @note None +* +*******************************************************************************/ +u32 ImageCheckID(u32 FlashOffsetAddress){ + u32 ID; + + /* + * Read in the header info + */ + MoveImage(FlashOffsetAddress + IMAGE_IDENT_OFFSET, (u32)&ID, 4); + + /* + * Check the ID, make sure image is XLNX format + */ + if (ID != IMAGE_IDENT){ + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/****************************************************************************** +* +* This function NextValidImageCheck search for valid boot image +* +* @param None +* +* @return +* - XST_SUCCESS if valid image found +* - XST_FAILURE if no image found +* +* @note None +* +*******************************************************************************/ +u32 NextValidImageCheck(void) +{ + u32 ImageBaseAddr; + u32 MultiBootReg; + u32 BootDevMaxSize=0; + + fsbl_printf(DEBUG_GENERAL, "Searching For Next Valid Image"); + + /* + * Setting variable with maximum flash size based on boot mode + */ +#ifdef XPAR_PS7_QSPI_LINEAR_0_S_AXI_BASEADDR + if (FlashReadBaseAddress == XPS_QSPI_LINEAR_BASEADDR) { + BootDevMaxSize = QspiFlashSize; + } +#endif + + if (FlashReadBaseAddress == XPS_NAND_BASEADDR) { + BootDevMaxSize = NAND_FLASH_SIZE; + } + + if (FlashReadBaseAddress == XPS_NOR_BASEADDR) { + BootDevMaxSize = NOR_FLASH_SIZE; + } + + /* + * Read the multiboot register + */ + MultiBootReg = XDcfg_ReadReg(DcfgInstPtr->Config.BaseAddr, + XDCFG_MULTIBOOT_ADDR_OFFSET); + + /* + * Compute the image start address + */ + ImageBaseAddr = (MultiBootReg & PCAP_MBOOT_REG_REBOOT_OFFSET_MASK) + * GOLDEN_IMAGE_OFFSET; + + /* + * Valid image search continue till end of the flash + * With increment 32KB in each iteration + */ + while (ImageBaseAddr < BootDevMaxSize) { + + fsbl_printf(DEBUG_INFO,"."); + + /* + * Valid image search using XLNX pattern at fixed offset + * and header checksum + */ + if ((ImageCheckID(ImageBaseAddr) == XST_SUCCESS) && + (HeaderChecksum(ImageBaseAddr) == XST_SUCCESS)) { + + fsbl_printf(DEBUG_GENERAL, "\r\nImage found, offset: 0x%.8x\r\n", + ImageBaseAddr); + /* + * Update multiboot register + */ + XDcfg_WriteReg(DcfgInstPtr->Config.BaseAddr, + XDCFG_MULTIBOOT_ADDR_OFFSET, + MultiBootReg); + + return XST_SUCCESS; + } + + /* + * Increment mulitboot count + */ + MultiBootReg++; + + /* + * Compute the image start address + */ + ImageBaseAddr = (MultiBootReg & PCAP_MBOOT_REG_REBOOT_OFFSET_MASK) + * GOLDEN_IMAGE_OFFSET; + } + + return XST_FAILURE; +} + +/******************************************************************************/ +/** +* +* This function Checks for the ddr initialization completion +* +* @param None. +* +* @return +* - XST_SUCCESS if the initialization is successful +* - XST_FAILURE if the initialization is NOT successful +* +* @note None. +* +****************************************************************************/ +u32 DDRInitCheck(void) +{ + u32 ReadVal; + + /* + * Write and Read from the DDR location for sanity checks + */ + Xil_Out32(DDR_START_ADDR, DDR_TEST_PATTERN); + ReadVal = Xil_In32(DDR_START_ADDR); + if (ReadVal != DDR_TEST_PATTERN) { + return XST_FAILURE; + } + + /* + * Write and Read from the DDR location for sanity checks + */ + Xil_Out32(DDR_START_ADDR + DDR_TEST_OFFSET, DDR_TEST_PATTERN); + ReadVal = Xil_In32(DDR_START_ADDR + DDR_TEST_OFFSET); + if (ReadVal != DDR_TEST_PATTERN) { + return XST_FAILURE; + } + + return XST_SUCCESS; +} diff --git a/quad/xsdk_workspace/zybo_fsbl/src/md5.c b/quad/xsdk_workspace/zybo_fsbl/src/md5.c new file mode 100644 index 0000000000000000000000000000000000000000..1aa0819001d70a519d62e404ecdf96b66cce7a8f --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/md5.c @@ -0,0 +1,484 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + * The licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/*****************************************************************************/ +/** +* +* @file md5.c +* +* Contains code to calculate checksum using md5 algorithm +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 5.00a sgd 05/17/13 Initial release +* +* +* </pre> +* +* @note +* +******************************************************************************/ +/****************************** Include Files *********************************/ + +#include "md5.h" + +/******************************************************************************/ +/** +* +* This function sets the memory +* +* @param dest +* +* @param ch +* +* @param count +* +* @return None +* +* @note None +* +****************************************************************************/ +inline void * _memset( void *dest, int ch, u32 count ) +{ + register char *dst8 = (char*)dest; + + while( count-- ) + *dst8++ = ch; + + return dest; +} + +/******************************************************************************/ +/** +* +* This function copy the memory +* +* @param dest +* +* @param ch +* +* @param count +* +* @return None +* +* @note None +* +****************************************************************************/ +inline void * _memcpy( void *dest, const void *src, + u32 count, boolean doByteSwap ) +{ + register char * dst8 = (char*)dest; + register char * src8 = (char*)src; + + if( doByteSwap == FALSE ) { + while( count-- ) + *dst8++ = *src8++; + } else { + count /= sizeof( u32 ); + + while( count-- ) { + dst8[ 0 ] = src8[ 3 ]; + dst8[ 1 ] = src8[ 2 ]; + dst8[ 2 ] = src8[ 1 ]; + dst8[ 3 ] = src8[ 0 ]; + + dst8 += 4; + src8 += 4; + } + } + + return dest; +} + +/******************************************************************************/ +/** +* +* This function is the core of the MD5 algorithm, +* this alters an existing MD5 hash to +* reflect the addition of 16 longwords of new data. MD5Update blocks +* the data and converts bytes into longwords for this routine. +* +* Use binary integer part of the sine of integers (Radians) as constants. +* Calculated as: +* +* for( i = 0; i < 63; i++ ) +* k[ i ] := floor( abs( sin( i + 1 ) ) × pow( 2, 32 ) ) +* +* Following number is the per-round shift amount. +* +* @param dest +* +* @param ch +* +* @param count +* +* @return None +* +* @note None +* +****************************************************************************/ +void MD5Transform( u32 *buffer, u32 *intermediate ) +{ + register u32 a, b, c, d; + + a = buffer[ 0 ]; + b = buffer[ 1 ]; + c = buffer[ 2 ]; + d = buffer[ 3 ]; + + MD5_STEP( F1, a, b, c, d, intermediate[ 0 ] + 0xd76aa478, 7 ); + MD5_STEP( F1, d, a, b, c, intermediate[ 1 ] + 0xe8c7b756, 12 ); + MD5_STEP( F1, c, d, a, b, intermediate[ 2 ] + 0x242070db, 17 ); + MD5_STEP( F1, b, c, d, a, intermediate[ 3 ] + 0xc1bdceee, 22 ); + MD5_STEP( F1, a, b, c, d, intermediate[ 4 ] + 0xf57c0faf, 7 ); + MD5_STEP( F1, d, a, b, c, intermediate[ 5 ] + 0x4787c62a, 12 ); + MD5_STEP( F1, c, d, a, b, intermediate[ 6 ] + 0xa8304613, 17 ); + MD5_STEP( F1, b, c, d, a, intermediate[ 7 ] + 0xfd469501, 22 ); + MD5_STEP( F1, a, b, c, d, intermediate[ 8 ] + 0x698098d8, 7 ); + MD5_STEP( F1, d, a, b, c, intermediate[ 9 ] + 0x8b44f7af, 12 ); + MD5_STEP( F1, c, d, a, b, intermediate[ 10 ] + 0xffff5bb1, 17 ); + MD5_STEP( F1, b, c, d, a, intermediate[ 11 ] + 0x895cd7be, 22 ); + MD5_STEP( F1, a, b, c, d, intermediate[ 12 ] + 0x6b901122, 7 ); + MD5_STEP( F1, d, a, b, c, intermediate[ 13 ] + 0xfd987193, 12 ); + MD5_STEP( F1, c, d, a, b, intermediate[ 14 ] + 0xa679438e, 17 ); + MD5_STEP( F1, b, c, d, a, intermediate[ 15 ] + 0x49b40821, 22 ); + + MD5_STEP( F2, a, b, c, d, intermediate[ 1 ] + 0xf61e2562, 5 ); + MD5_STEP( F2, d, a, b, c, intermediate[ 6 ] + 0xc040b340, 9 ); + MD5_STEP( F2, c, d, a, b, intermediate[ 11 ] + 0x265e5a51, 14 ); + MD5_STEP( F2, b, c, d, a, intermediate[ 0 ] + 0xe9b6c7aa, 20 ); + MD5_STEP( F2, a, b, c, d, intermediate[ 5 ] + 0xd62f105d, 5 ); + MD5_STEP( F2, d, a, b, c, intermediate[ 10 ] + 0x02441453, 9 ); + MD5_STEP( F2, c, d, a, b, intermediate[ 15 ] + 0xd8a1e681, 14 ); + MD5_STEP( F2, b, c, d, a, intermediate[ 4 ] + 0xe7d3fbc8, 20 ); + MD5_STEP( F2, a, b, c, d, intermediate[ 9 ] + 0x21e1cde6, 5 ); + MD5_STEP( F2, d, a, b, c, intermediate[ 14 ] + 0xc33707d6, 9 ); + MD5_STEP( F2, c, d, a, b, intermediate[ 3 ] + 0xf4d50d87, 14 ); + MD5_STEP( F2, b, c, d, a, intermediate[ 8 ] + 0x455a14ed, 20 ); + MD5_STEP( F2, a, b, c, d, intermediate[ 13 ] + 0xa9e3e905, 5 ); + MD5_STEP( F2, d, a, b, c, intermediate[ 2 ] + 0xfcefa3f8, 9 ); + MD5_STEP( F2, c, d, a, b, intermediate[ 7 ] + 0x676f02d9, 14 ); + MD5_STEP( F2, b, c, d, a, intermediate[ 12 ] + 0x8d2a4c8a, 20 ); + + MD5_STEP( F3, a, b, c, d, intermediate[ 5 ] + 0xfffa3942, 4 ); + MD5_STEP( F3, d, a, b, c, intermediate[ 8 ] + 0x8771f681, 11 ); + MD5_STEP( F3, c, d, a, b, intermediate[ 11 ] + 0x6d9d6122, 16 ); + MD5_STEP( F3, b, c, d, a, intermediate[ 14 ] + 0xfde5380c, 23 ); + MD5_STEP( F3, a, b, c, d, intermediate[ 1 ] + 0xa4beea44, 4 ); + MD5_STEP( F3, d, a, b, c, intermediate[ 4 ] + 0x4bdecfa9, 11 ); + MD5_STEP( F3, c, d, a, b, intermediate[ 7 ] + 0xf6bb4b60, 16 ); + MD5_STEP( F3, b, c, d, a, intermediate[ 10 ] + 0xbebfbc70, 23 ); + MD5_STEP( F3, a, b, c, d, intermediate[ 13 ] + 0x289b7ec6, 4 ); + MD5_STEP( F3, d, a, b, c, intermediate[ 0 ] + 0xeaa127fa, 11 ); + MD5_STEP( F3, c, d, a, b, intermediate[ 3 ] + 0xd4ef3085, 16 ); + MD5_STEP( F3, b, c, d, a, intermediate[ 6 ] + 0x04881d05, 23 ); + MD5_STEP( F3, a, b, c, d, intermediate[ 9 ] + 0xd9d4d039, 4 ); + MD5_STEP( F3, d, a, b, c, intermediate[ 12 ] + 0xe6db99e5, 11 ); + MD5_STEP( F3, c, d, a, b, intermediate[ 15 ] + 0x1fa27cf8, 16 ); + MD5_STEP( F3, b, c, d, a, intermediate[ 2 ] + 0xc4ac5665, 23 ); + + MD5_STEP( F4, a, b, c, d, intermediate[ 0 ] + 0xf4292244, 6 ); + MD5_STEP( F4, d, a, b, c, intermediate[ 7 ] + 0x432aff97, 10 ); + MD5_STEP( F4, c, d, a, b, intermediate[ 14 ] + 0xab9423a7, 15 ); + MD5_STEP( F4, b, c, d, a, intermediate[ 5 ] + 0xfc93a039, 21 ); + MD5_STEP( F4, a, b, c, d, intermediate[ 12 ] + 0x655b59c3, 6 ); + MD5_STEP( F4, d, a, b, c, intermediate[ 3 ] + 0x8f0ccc92, 10 ); + MD5_STEP( F4, c, d, a, b, intermediate[ 10 ] + 0xffeff47d, 15 ); + MD5_STEP( F4, b, c, d, a, intermediate[ 1 ] + 0x85845dd1, 21 ); + MD5_STEP( F4, a, b, c, d, intermediate[ 8 ] + 0x6fa87e4f, 6 ); + MD5_STEP( F4, d, a, b, c, intermediate[ 15 ] + 0xfe2ce6e0, 10 ); + MD5_STEP( F4, c, d, a, b, intermediate[ 6 ] + 0xa3014314, 15 ); + MD5_STEP( F4, b, c, d, a, intermediate[ 13 ] + 0x4e0811a1, 21 ); + MD5_STEP( F4, a, b, c, d, intermediate[ 4 ] + 0xf7537e82, 6 ); + MD5_STEP( F4, d, a, b, c, intermediate[ 11 ] + 0xbd3af235, 10 ); + MD5_STEP( F4, c, d, a, b, intermediate[ 2 ] + 0x2ad7d2bb, 15 ); + MD5_STEP( F4, b, c, d, a, intermediate[ 9 ] + 0xeb86d391, 21 ); + + buffer[ 0 ] += a; + buffer[ 1 ] += b; + buffer[ 2 ] += c; + buffer[ 3 ] += d; + +} + +/******************************************************************************/ +/** +* +* This function Start MD5 accumulation +* Set bit count to 0 and buffer to mysterious initialization constants +* +* @param +* +* @return None +* +* @note None +* +****************************************************************************/ +inline void MD5Init( MD5Context *context ) +{ + + context->buffer[ 0 ] = 0x67452301; + context->buffer[ 1 ] = 0xefcdab89; + context->buffer[ 2 ] = 0x98badcfe; + context->buffer[ 3 ] = 0x10325476; + + context->bits[ 0 ] = 0; + context->bits[ 1 ] = 0; + +} + + +/******************************************************************************/ +/** +* +* This function updates context to reflect the concatenation of another +* buffer full of bytes +* +* @param +* +* @param +* +* @param +* +* @param +* +* @return None +* +* @note None +* +****************************************************************************/ +inline void MD5Update( MD5Context *context, u8 *buffer, + u32 len, boolean doByteSwap ) +{ + register u32 temp; + register u8 * p; + + /* + * Update bitcount + */ + + temp = context->bits[ 0 ]; + + if( ( context->bits[ 0 ] = temp + ( (u32)len << 3 ) ) < temp ) { + /* + * Carry from low to high + */ + context->bits[ 1 ]++; + } + + context->bits[ 1 ] += len >> 29; + + /* + * Bytes already in shsInfo->data + */ + + temp = ( temp >> 3 ) & 0x3f; + + /* + * Handle any leading odd-sized chunks + */ + + if( temp ) { + p = (u8 *)context->intermediate + temp; + + temp = MD5_SIGNATURE_BYTE_SIZE - temp; + + if( len < temp ) { + _memcpy( p, buffer, len, doByteSwap ); + return; + } + + _memcpy( p, buffer, temp, doByteSwap ); + + MD5Transform( context->buffer, (u32 *)context->intermediate ); + + buffer += temp; + len -= temp; + + } + + /* + * Process data in 64-byte, 512 bit, chunks + */ + + while( len >= MD5_SIGNATURE_BYTE_SIZE ) { + _memcpy( context->intermediate, buffer, MD5_SIGNATURE_BYTE_SIZE, + doByteSwap ); + + MD5Transform( context->buffer, (u32 *)context->intermediate ); + + buffer += MD5_SIGNATURE_BYTE_SIZE; + len -= MD5_SIGNATURE_BYTE_SIZE; + + } + + /* + * Handle any remaining bytes of data + */ + _memcpy( context->intermediate, buffer, len, doByteSwap ); + +} + +/******************************************************************************/ +/** +* +* This function final wrap-up - pad to 64-byte boundary with the bit pattern +* 1 0* (64-bit count of bits processed, MSB-first +* +* @param +* +* @param +* +* @param +* +* @param +* +* @return None +* +* @note None +* +****************************************************************************/ +inline void MD5Final( MD5Context *context, u8 *digest, + boolean doByteSwap ) +{ + u32 count; + u8 * p; + + /* + * Compute number of bytes mod 64 + */ + count = ( context->bits[ 0 ] >> 3 ) & 0x3F; + + /* + * Set the first char of padding to 0x80. This is safe since there is + * always at least one byte free + */ + p = context->intermediate + count; + *p++ = 0x80; + + /* + * Bytes of padding needed to make 64 bytes + */ + count = MD5_SIGNATURE_BYTE_SIZE - 1 - count; + + /* + * Pad out to 56 mod 64 + */ + if( count < 8 ) { + /* + * Two lots of padding: Pad the first block to 64 bytes + */ + _memset( p, 0, count ); + + MD5Transform( context->buffer, (u32 *)context->intermediate ); + + /* + * Now fill the next block with 56 bytes + */ + _memset( context->intermediate, 0, 56 ); + } else { + /* + * Pad block to 56 bytes + */ + _memset( p, 0, count - 8 ); + } + + /* + * Append length in bits and transform + */ + ( (u32 *)context->intermediate )[ 14 ] = context->bits[ 0 ]; + ( (u32 *)context->intermediate )[ 15 ] = context->bits[ 1 ]; + + MD5Transform( context->buffer, (u32 *)context->intermediate ); + + /* + * Now return the digest + */ + _memcpy( digest, context->buffer, 16, doByteSwap ); +} + +/******************************************************************************/ +/** +* +* This function calculate and store in 'digest' the MD5 digest of 'len' bytes at +* 'input'. 'digest' must have enough space to hold 16 bytes +* +* @param +* +* @param +* +* @param +* +* @param +* +* @return None +* +* @note None +* +****************************************************************************/ +void md5( u8 *input, u32 len, u8 *digest, boolean doByteSwap ) +{ + MD5Context context; + + MD5Init( &context ); + + MD5Update( &context, input, len, doByteSwap ); + + MD5Final( &context, digest, doByteSwap ); +} diff --git a/quad/xsdk_workspace/zybo_fsbl/src/md5.h b/quad/xsdk_workspace/zybo_fsbl/src/md5.h new file mode 100644 index 0000000000000000000000000000000000000000..a00c17b1a1f3bba0a90b0105b93e2746aff3070c --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/md5.h @@ -0,0 +1,129 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file md5.h +* +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 5.00a sgd 05/17/13 Initial release +* +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___MD5_H___ +#define ___MD5_H___ + + +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ + +#include "xil_types.h" + +/************************** Constant Definitions *****************************/ + +#define MD5_SIGNATURE_BYTE_SIZE 64 + +/**************************** Type Definitions *******************************/ + +typedef u8 boolean; +typedef u8 signature[ MD5_SIGNATURE_BYTE_SIZE ]; + +struct MD5Context + { + u32 buffer[ 4 ]; + u32 bits[ 2 ]; + signature intermediate; + }; +typedef struct MD5Context MD5Context; + +/***************** Macros (Inline Functions) Definitions *********************/ + +/* + * The four core functions - F1 is optimized somewhat + */ +#define F1( x, y, z ) ( z ^ ( x & ( y ^ z ) ) ) +#define F2( x, y, z ) F1( z, x, y ) +#define F3( x, y, z ) ( x ^ y ^ z ) +#define F4( x, y, z ) ( y ^ ( x | ~z ) ) + + +/* + * This is the central step in the MD5 algorithm + */ +#define MD5_STEP( f, w, x, y, z, data, s ) \ + ( w += f( x, y, z ) + data, w = w << s | w >> ( 32 - s ), w += x ) + + +/************************** Function Prototypes ******************************/ + +void * _memset( void *dest, int ch, u32 count ); + +void * _memcpy( void *dest, const void *src, u32 count, boolean doByteSwap ); + +void MD5Transform( u32 *buffer, u32 *intermediate ); + +void MD5Init( MD5Context *context ); + +void MD5Update( MD5Context *context, u8 *buffer, u32 len, boolean doByteSwap ); + +void MD5Final( MD5Context *context, u8 *digest, boolean doByteSwap ); + +void md5( u8 *input, u32 len, u8 *digest, boolean doByteSwap ); + +/************************** Variable Definitions *****************************/ + +#ifdef __cplusplus +} +#endif + + +#endif /* ___MD5_H___ */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/mmc.c b/quad/xsdk_workspace/zybo_fsbl/src/mmc.c new file mode 100644 index 0000000000000000000000000000000000000000..8543b10c404dd636f1c595ba0842e5aee91748ed --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/mmc.c @@ -0,0 +1,1181 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file mmc.c +* +* SD interface to FatFS +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a bh 05/28/11 Initial release +* 1.00a nm 03/20/12 Changed the SD base clock divider from + 0x40 to 0x04. +* 3.00a mb 08/16/12 Added the flag XPAR_PS7_SD_0_S_AXI_BASEADDR +* 3.00a sgd 08/16/12 SD Boot time improvement +* Added SD high speed and 4bit support check +* 4.00a sgd 02/28/13 Code cleanup +* 5.00a sgd 05/17/13 Added MMC support +* To support MMC, added two separate functions +* sd_init for SD initialization +* mmc_init for MMC initialization +* +* </pre> +* +* @note +* +******************************************************************************/ +#include "xparameters.h" +#include "fsbl.h" +#ifdef XPAR_PS7_SD_0_S_AXI_BASEADDR + +#include "diskio.h" /* Common include file for FatFs and disk I/O layer */ +#include "ff.h" +#include "xil_types.h" +#include "sd_hardware.h" +#include "sleep.h" +#ifndef PEEP_CODE +#include "ps7_init.h" +#endif + +/* + * Map logical volume to physical drive + partition. + * Logical X [0-3] to Physical 0, partition X + */ +#if _MULTI_PARTITION +const PARTITION VolToPart[] = { + {0, 0}, {0, 1}, {0, 2}, {0, 3} }; +#endif + +static DSTATUS Stat; /* Disk status */ +static BYTE CardType; /* b0:MMC, b1:SDv1, b2:SDv2, b3:Block addressing */ + +/* Block Count variable */ +static u16 blkcnt; +/* Block Size variable */ +static u16 blksize; + +/* ADMA2 descriptor table */ +static u32 desc_table[4]; + +#define sd_out32(OutAddress, Value) Xil_Out32((XPAR_PS7_SD_0_S_AXI_BASEADDR) + (OutAddress), (Value)) +#define sd_out16(OutAddress, Value) Xil_Out16((XPAR_PS7_SD_0_S_AXI_BASEADDR) + (OutAddress), (Value)) +#define sd_out8(OutAddress, Value) Xil_Out8((XPAR_PS7_SD_0_S_AXI_BASEADDR) + (OutAddress), (Value)) + +#define sd_in32(InAddress) Xil_In32((XPAR_PS7_SD_0_S_AXI_BASEADDR) + (InAddress)) +#define sd_in16(InAddress) Xil_In16((XPAR_PS7_SD_0_S_AXI_BASEADDR) + (InAddress)) +#define sd_in8(InAddress) Xil_In8((XPAR_PS7_SD_0_S_AXI_BASEADDR) + (InAddress)) + +#ifdef MMC_SUPPORT + +#define MMC_CLK_52M 52000000 +#define MMC_CLK_26M 26000000 +#define MMC_HS_SUPPORT 0x1 +#define MMC_4BIT_SUPPORT 0x1 +#define EXT_CSD_BUS_WIDTH 183 +#define EXT_CSD_HS_TIMING 185 +#define MMC_SWITCH_MODE_WRITE_BYTE 0x03 +#define MMC_OCR_REG_VALUE ((0x1 << 30) | (0x1FF << 15)) + +static DRESULT mmc_init(void); +#else + +static DRESULT sd_init(void); + +#endif +/******************************************************************************/ +/** +* +* This function Initializes the SD controller +* +* @param None +* +* @return None +* +* @note None +* +****************************************************************************/ +static void init_port(void) +{ + unsigned clk; + unsigned clk_div; + + Stat = STA_NOINIT; + + /* + * Power off the card + */ + sd_out8(SD_PWR_CTRL_R, 0); + + /* + * Disable interrupts + */ + sd_out32(SD_SIG_ENA_R, 0); + + /* + * Perform soft reset + */ + sd_out8(SD_SOFT_RST_R, SD_RST_ALL); + + /* + * Wait for reset to complete + */ + while (sd_in8(SD_SOFT_RST_R)) { + ; + } + + /* + * Power on the card + */ + sd_out8(SD_PWR_CTRL_R, SD_POWER_33|SD_POWER_ON); + + /* + * Enable ADMA2 + */ + sd_out8(SD_HOST_CTRL_R, SD_HOST_ADMA2); + + clk_div = (SDIO_FREQ/SD_CLK_400K); + /* + * Enable Internal clock and wait for it to stabilize + */ + clk = (clk_div << SD_DIV_SHIFT) | SD_CLK_INT_EN; + sd_out16(SD_CLK_CTL_R, clk); + do { + clk = sd_in16(SD_CLK_CTL_R); + } while (!(clk & SD_CLK_INT_STABLE)); + + /* + * Enable SD clock + */ + clk |= SD_CLK_SD_EN; + sd_out16(SD_CLK_CTL_R, clk); + + sd_out32(SD_SIG_ENA_R, 0xFFFFFFFF); + sd_out32(SD_INT_ENA_R, 0xFFFFFFFF); +} + + +/******************************************************************************/ +/** +* +* Module Private Functions +* +****************************************************************************/ +/* + * MMC/SD commands + */ +#define CMD0 (0) /* GO_IDLE_STATE */ +#define CMD1 (1) /* SEND_OP_COND */ +#define ACMD41 (0x80+41) /* SEND_OP_COND (SDC) */ +#define CMD2 (2) /* SEND_CID */ +#define CMD3 (3) /* RELATIVE_ADDR */ +#define CMD4 (4) /* SET_DSR */ +#define CMD5 (5) /* SLEEP_WAKE (SDC) */ +#define CMD6 (6) /* SWITCH_FUNC */ +#define ACMD6 (0x80+6) /* SET_BUS_WIDTH (SDC) */ +#define CMD7 (7) /* SELECT */ +#define CMD8 (8) /* SEND_IF_COND/SEND_EXT_CSD */ +#define CMD9 (9) /* SEND_CSD */ +#define CMD10 (10) /* SEND_CID */ +#define CMD12 (12) /* STOP_TRANSMISSION */ +#define ACMD13 (0x80+13) /* SD_STATUS (SDC) */ +#define CMD16 (16) /* SET_BLOCKLEN */ +#define CMD17 (17) /* READ_SINGLE_BLOCK */ +#define CMD18 (18) /* READ_MULTIPLE_BLOCK */ +#define CMD23 (23) /* SET_BLOCK_COUNT */ +#define ACMD23 (0x80+23) /* SET_WR_BLK_ERASE_COUNT (SDC) */ +#define CMD24 (24) /* WRITE_BLOCK */ +#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */ +#define CMD41 (41) /* SEND_OP_COND (ACMD) */ +#define ACMD42 (0x80+42) /* SET_CLR_CARD_DETECT (ACMD) */ +#define ACMD51 (0x80+51) /* SEND_SCR */ +#define CMD52 (52) /* */ +#define CMD55 (55) /* APP_CMD */ +#define CMD58 (58) /* READ_OCR */ + +/* + * Card type flags (CardType) + */ +#define CT_MMC 0x01 /* MMC ver 3 */ +#define CT_SD1 0x02 /* SD ver 1 */ +#define CT_SD2 0x04 /* SD ver 2 */ +#define CT_SDC (CT_SD1|CT_SD2) /* SD */ +#define CT_BLOCK 0x08 /* Block addressing */ + + +/******************************************************************************/ +/** +* +* This function Determine the value of the controller transfer register +* for the provided +* +* @param cmd command index +* +* @return cmd value +* +* @note None +* +****************************************************************************/ +static int make_command (unsigned cmd) +{ + unsigned retval; + + retval = cmd << 8; + +#define RSP_NONE SD_CMD_RESP_NONE +#define RSP_R1 (SD_CMD_INDEX|SD_CMD_RESP_48 |SD_CMD_CRC) +#define RSP_R1b (SD_CMD_INDEX|SD_CMD_RESP_48_BUSY|SD_CMD_CRC) +#define RSP_R2 (SD_CMD_CRC |SD_CMD_RESP_136) +#define RSP_R3 (SD_CMD_RESP_48) +#define RSP_R6 (SD_CMD_INDEX|SD_CMD_RESP_48_BUSY|SD_CMD_CRC) + + switch(cmd) { + case CMD0: + retval |= (SD_CMD_RESP_NONE); + break; + case CMD1: + retval |= RSP_R3; + break; + case CMD2: + retval |= RSP_R2; + break; + case CMD3: + retval |= RSP_R6; + break; + case CMD4: + retval |= (SD_CMD_RESP_NONE); + break; + case CMD5: + retval |= RSP_R1b; + break; +#ifdef MMC_SUPPORT + case CMD6: + retval |= RSP_R1b; + break; +#else + case CMD6: + retval |= RSP_R1 | SD_CMD_DATA; + break; +#endif + case ACMD6: + retval |= RSP_R1; + break; + case CMD7: + retval |= RSP_R1; + break; +#ifdef MMC_SUPPORT + case CMD8: + retval |= RSP_R1 | SD_CMD_DATA; + break; +#else + case CMD8: + retval |= RSP_R1; + break; +#endif + case CMD9: + retval |= RSP_R2; + break; + case CMD10: + case CMD12: + case ACMD13: + case CMD16: + retval |= RSP_R1; + break; + case CMD17: + case CMD18: + retval |= RSP_R1|SD_CMD_DATA; + break; + case CMD23: + case ACMD23: + case CMD24: + case CMD25: + case CMD41: + retval |= RSP_R3; + break; + case ACMD42: + retval |= RSP_R1; + break; + case ACMD51: + retval |= RSP_R1|SD_CMD_DATA; + break; + case CMD52: + case CMD55: + retval |= RSP_R1; + break; + case CMD58: + break; + } + + return retval; +} + +/******************************************************************************/ +/** +* +* This function Determine the value of the controller transfer register +* for the provided +* +* @param cmd Command byte +* +* @param arg Argument +* +* @param response Response from device +* +* @return 1 on success +* 0 on timeout +* +* @note None +* +****************************************************************************/ +static BYTE send_cmd (BYTE cmd, DWORD arg, DWORD *response) +{ + u32 status; + u16 cmdreg; + + if (response) { + *response = 0; + } + + /* + * Wait until the device is willing to accept commands + */ + do { + status = sd_in32(SD_PRES_STATE_R); + } while (status & (SD_CMD_INHIBIT|SD_DATA_INHIBIT)); + + /* + * Clear all pending interrupt status + */ + sd_out32(SD_INT_STAT_R, 0xFFFFFFFF); + + /* + * 512 byte block size. + * This is only relevant for data commands. + */ + sd_out16(SD_BLOCK_SZ_R, blksize); + sd_out16(SD_BLOCK_CNT_R, blkcnt); + + /* + * Setting timeout to max value + */ + sd_out8(SD_TIMEOUT_CTL_R, 0xE); + + sd_out32(SD_ARG_R, arg); + + if (cmd!=CMD18) { + sd_out16(SD_TRNS_MODE_R, SD_TRNS_READ|SD_TRNS_DMA); + } else { + /* + * Set the transfer mode to read, DMA, multiple block + * (applicable only to data commands) + * This is all that this software supports. + */ + sd_out16(SD_TRNS_MODE_R, SD_TRNS_READ|SD_TRNS_MULTI| + SD_TRNS_ACMD12|SD_TRNS_BLK_CNT_EN|SD_TRNS_DMA); + } + + /* + * Initiate the command + */ + cmdreg = make_command(cmd); + sd_out16(SD_CMD_R, cmdreg); + + /* + * Poll until operation complete + */ + while (1) { + status = sd_in32(SD_INT_STAT_R); + if (status & SD_INT_ERROR) { + fsbl_printf(DEBUG_GENERAL,"send_cmd: Error: (0x%08x) cmd: %d arg: 0x%x\n", + status, cmd, arg); + sd_out8(SD_SOFT_RST_R, SD_RST_CMD|SD_RST_DATA); + + return 0; + } + /* + * Check for Command complete + */ + if (status & SD_INT_CMD_CMPL) { + sd_out32(SD_INT_STAT_R, SD_INT_CMD_CMPL); + break; + } + } + + status = sd_in32(SD_RSP_R); + if (response) { + *response = status; + } + + return 1; +} + + +/******************************************************************************/ +/** +* +* This function Setup ADMA2 for data transfer +* +* @param buff_ptr +* +* @return None +* +* @note None +* +****************************************************************************/ +void setup_adma2_trans(BYTE *buff_ptr) +{ + /* + * Set descriptor table + */ + desc_table[0] = ((blkcnt*blksize) << DESC_ATBR_LEN_SHIFT)| + DESC_ATBR_ACT_TRAN|DESC_ATBR_END|DESC_ATBR_VALID; + desc_table[1] = (u32)buff_ptr; + + /* + * Set ADMA system address register + */ + sd_out32(SD_ADMA_ADDR_R, (u32)&desc_table[0]); +} + + +/******************************************************************************/ +/** +* +* This function is wait for DMA transfer complete +* +* @param None +* +* @return 0 for failure +* 1 for success +* @note None +* +****************************************************************************/ +static BYTE dma_trans_cmpl(void) +{ + u32 status; + + /* + * Poll until operation complete + */ + while (1) { + status = sd_in32(SD_INT_STAT_R); + if (status & SD_INT_ERROR) { + fsbl_printf(DEBUG_GENERAL,"dma_trans_cmpl: Error: (0x%08x)\r\n", + status); + return 0; + } + + /* + * Check for Transfer complete + */ + if (status & SD_INT_TRNS_CMPL) { + sd_out32(SD_INT_STAT_R, SD_INT_TRNS_CMPL); + break; + } + } + return 1; +} + +/*-------------------------------------------------------------------------- + + Public Functions + +---------------------------------------------------------------------------*/ + + +/*-----------------------------------------------------------------------*/ +/* Get Disk Status */ +/*-----------------------------------------------------------------------*/ + +DSTATUS disk_status ( + BYTE drv /* Drive number (0) */ +) +{ + DSTATUS s = Stat; + unsigned statusreg; + + statusreg = sd_in32(SD_PRES_STATE_R); + if (!(statusreg & SD_CARD_INS)) { + s = STA_NODISK | STA_NOINIT; + } else { + s &= ~STA_NODISK; + if (statusreg & SD_CARD_WP) + s |= STA_PROTECT; + else + s &= ~STA_PROTECT; + } + Stat = s; + + return s; +} + +/*-----------------------------------------------------------------------*/ +/* Initialize Disk Drive */ +/*-----------------------------------------------------------------------*/ + +DSTATUS disk_initialize ( + BYTE drv /* Physical drive number (0) */ +) +{ + DSTATUS s; + + /* + * Check if card is in the socket + */ + s = disk_status(drv); + if (s & STA_NODISK) { + fsbl_printf(DEBUG_GENERAL,"No SD card present.\n"); + return s; + } + + /* + * Initialize the host controller + */ + init_port(); + +#ifdef MMC_SUPPORT + s = mmc_init(); + if(s != RES_OK) { + fsbl_printf(DEBUG_GENERAL,"MMC Initialization Failed.\n"); + return s; + } +#else + s = sd_init(); + if(s != RES_OK) { + fsbl_printf(DEBUG_GENERAL,"SD Initialization Failed.\n"); + return s; + } +#endif + + if (CardType) /* Initialization succeeded */ + s &= ~STA_NOINIT; + else /* Initialization failed */ + s |= STA_NOINIT; + Stat = s; + + return s; +} + + + +/*-----------------------------------------------------------------------*/ +/* Read Sector(s) */ +/*-----------------------------------------------------------------------*/ + +DRESULT disk_read ( + BYTE drv, /* Physical drive number (0) */ + BYTE *buff, /* Pointer to the data buffer to store read data */ + DWORD sector, /* Start sector number (LBA) */ + BYTE count /* Sector count (1..128) */ +) +{ + DSTATUS s; + + s = disk_status(drv); + if (s & STA_NOINIT) return RES_NOTRDY; + if (!count) return RES_PARERR; + /* Convert LBA to byte address if needed */ + if (!(CardType & CT_BLOCK)) sector *= SD_BLOCK_SZ; + + blkcnt = count; + blksize= SD_BLOCK_SZ; + + /* set adma2 for transfer */ + setup_adma2_trans(buff); + + /* Multiple block read */ + send_cmd(CMD18, sector, NULL); + + /* check for dma transfer complete */ + if (!dma_trans_cmpl()) { + return RES_ERROR; + } + + return RES_OK; +} + + +/*-----------------------------------------------------------------------*/ +/* Miscellaneous Functions */ +/*-----------------------------------------------------------------------*/ + +DRESULT disk_ioctl ( + BYTE drv, /* Physical drive number (0) */ + BYTE ctrl, /* Control code */ + void *buff /* Buffer to send/receive control data */ +) +{ + DRESULT res; + + if (disk_status(drv) & STA_NOINIT) /* Check if card is in the socket */ + return RES_NOTRDY; + + res = RES_ERROR; + switch (ctrl) { + case CTRL_SYNC : /* Make sure that no pending write process */ + break; + + case GET_SECTOR_COUNT : /* Get number of sectors on the disk (DWORD) */ + break; + + case GET_BLOCK_SIZE : /* Get erase block size in unit of sector (DWORD) */ + *(DWORD*)buff = 128; + res = RES_OK; + break; + + default: + res = RES_PARERR; + break; + } + + return res; +} + +/******************************************************************************/ +/** +* +* This function is User Provided Timer Function for FatFs module +* +* @param None +* +* @return DWORD +* +* @note None +* +****************************************************************************/ +DWORD get_fattime (void) +{ + return ((DWORD)(2010 - 1980) << 25) /* Fixed to Jan. 1, 2010 */ + | ((DWORD)1 << 21) + | ((DWORD)1 << 16) + | ((DWORD)0 << 11) + | ((DWORD)0 << 5) + | ((DWORD)0 >> 1); +} + + + +#ifdef MMC_SUPPORT +/* + * MMC initialization + */ +static DRESULT mmc_init(void) +{ + BYTE ty; + DSTATUS s; + DWORD response; + unsigned rca; + u16 regval; + u16 clk_div; + u32 argument; + u8 status_data[512]; + + ty= CT_MMC; + + /* + * Enter Idle state + */ + send_cmd(CMD0, 0, NULL); + + /* + * Wait for leaving idle state (CMD1 with HCS bit) + */ + while (1) { + + argument = MMC_OCR_REG_VALUE; + + s= send_cmd(CMD1, argument, &response); + if (s == 0) { + /* + * command error; probably an SD card + */ + ty = 0; + goto fail; + } + if (response & 1<<31) { + break; + } + } + + if (response & 1<<30) { + /* + * Card supports block addressing + */ + ty |= CT_BLOCK; + } + + /* + * Get CID + */ + send_cmd(CMD2, 0, &response); + + /* + * Set RCA + */ + rca = 0x1234; + send_cmd(CMD3, rca << 16, &response); + + /* + * Send CSD + */ + send_cmd(CMD9,rca<<16,&response); + + /* + * select card + */ + send_cmd(CMD7, rca << 16, &response); + + /* + * Switch the bus width to 4bit + */ + argument = (MMC_SWITCH_MODE_WRITE_BYTE << 24) | + (EXT_CSD_BUS_WIDTH << 16) | + (1 << 8); + send_cmd(CMD6, argument, &response); + + /* + * Delay for device to setup + */ + usleep(1000); + + /* + * Enable 4bit mode in controller + */ + regval = sd_in16(SD_HOST_CTRL_R); + regval |= SD_HOST_4BIT; + sd_out16(SD_HOST_CTRL_R, regval); + + /* + * Switch device to high speed + */ + argument = (MMC_SWITCH_MODE_WRITE_BYTE << 24) | + (EXT_CSD_HS_TIMING << 16) | + (1 << 8); + send_cmd(CMD6, argument, &response); + + /* + * Delay for device to setup + */ + usleep(1000); + + /* + * Verify Bus width switch to high speed support + */ + blkcnt = 1; + blksize= 512; + + /* + * Set adma2 for transfer + */ + setup_adma2_trans(&status_data[0]); + + /* + * Check for high speed support switch + */ + send_cmd(CMD8, 0x0, &response); + + /* + * Check for dma transfer complete + */ + if (!dma_trans_cmpl()) { + return RES_ERROR; + } + + /* + * Check for 4bit support + */ + if (status_data[EXT_CSD_BUS_WIDTH] == MMC_4BIT_SUPPORT) { + fsbl_printf(DEBUG_INFO, "Bus Width 4Bit\r\n"); + } + + + if (status_data[EXT_CSD_HS_TIMING] == MMC_HS_SUPPORT) { + fsbl_printf(DEBUG_INFO, "High Speed Mode\r\n"); + /* + * Disable SD clock and internal clock + */ + regval = sd_in16(SD_CLK_CTL_R); + regval &= ~(SD_CLK_SD_EN|SD_CLK_INT_EN); + sd_out16(SD_CLK_CTL_R, regval); + + clk_div = (SDIO_FREQ / MMC_CLK_52M); + if (!(SDIO_FREQ % MMC_CLK_52M)) { + clk_div -=1; + } + + /* + * Enable Internal clock and wait for it to stabilize + */ + regval = (clk_div << SD_DIV_SHIFT) | SD_CLK_INT_EN; + sd_out16(SD_CLK_CTL_R, regval); + do { + regval = sd_in16(SD_CLK_CTL_R); + } while (!(regval & SD_CLK_INT_STABLE)); + + /* + * Enable SD clock + */ + regval |= SD_CLK_SD_EN; + sd_out16(SD_CLK_CTL_R, regval); + + /* + * Enable high speed mode in controller + */ + regval = sd_in16(SD_HOST_CTRL_R); + regval |= SD_HOST_HS; + sd_out16(SD_HOST_CTRL_R, regval); + } else { + /* + * Disable SD clock and internal clock + */ + regval = sd_in16(SD_CLK_CTL_R); + regval &= ~(SD_CLK_SD_EN|SD_CLK_INT_EN); + sd_out16(SD_CLK_CTL_R, regval); + + /* + * Calculating clock divisor + */ + clk_div = (SDIO_FREQ / MMC_CLK_26M); + if (!(SDIO_FREQ % MMC_CLK_26M)) { + clk_div -=1; + } + + /* + * Enable Internal clock and wait for it to stabilize + */ + regval = (clk_div << SD_DIV_SHIFT) | SD_CLK_INT_EN; + sd_out16(SD_CLK_CTL_R, regval); + do { + regval = sd_in16(SD_CLK_CTL_R); + } while (!(regval & SD_CLK_INT_STABLE)); + + /* + * Enable SD clock + */ + regval |= SD_CLK_SD_EN; + sd_out16(SD_CLK_CTL_R, regval); + } + + /* + * Set R/W block length to 512 + */ + send_cmd(CMD16, SD_BLOCK_SZ, &response); + +fail: + CardType = ty; + + return RES_OK; +} + +#else +/* + * SD initialization + */ +DRESULT sd_init(void) +{ + BYTE ty; + DSTATUS s; + DWORD response; + unsigned rca; + u16 regval; + u8 status_data[64]; + u8 sd_4bit_flag=0; + u8 sd_hs_flag=0; + u16 clk_div; + + /* + * Enter Idle state + */ + send_cmd(CMD0, 0, NULL); + + ty = CT_SD1; + /* + * SDv2? + */ + if (send_cmd(CMD8, 0x1AA, &response) == 1) { + /* + * The card can work at vdd range of 2.7-3.6V + */ + if (response == 0x1AA) { + ty = CT_SD2; + } + } + + /* + * Wait for leaving idle state (ACMD41 with HCS bit) + */ + while (1) { + /* + * ACMD41, Set Operating Continuous + */ + send_cmd(CMD55, 0, NULL); + /* 0x00ff8000 */ + s = send_cmd(CMD41, 0x40300000, &response); + if (s == 0) { + /* + * command error; probably an MMC card + * presently unsupported; abort + */ + ty = 0; + goto fail; + } + if (response & 1<<31) { + break; + } + } + if (response & 1<<30) { + /* + * Card supports block addressing + */ + ty |= CT_BLOCK; + } + + /* + * Get CID + */ + send_cmd(CMD2, 0, &response); + + /* + * Get RCA + */ + rca = 0x1234; + send_cmd(CMD3, rca << 16, &response); + rca = response >> 16; + + /* + * select card + */ + send_cmd(CMD7, rca << 16, &response); + + /* + * Getting 4bit support information + */ + blkcnt = 1; + blksize= 8; + + /* + * Set adma2 for transfer + */ + setup_adma2_trans(&status_data[0]); + + /* + * Application specific command + */ + send_cmd(CMD55, rca << 16, &response); + + /* + * Read SD Configuration Register + */ + send_cmd(ACMD51, 0, &response); + + /* + * Check for dma transfer complete + */ + if (!dma_trans_cmpl()) { + return RES_ERROR; + } + + /* + * SD 4-bit support check + */ + if (status_data[1]&SD_4BIT_SUPPORT) { + sd_4bit_flag=1; + } + + /* + * Getting high speed support support information + */ + blkcnt = 1; + blksize= 64; + + /* + * Set adma2 for transfer + */ + setup_adma2_trans(&status_data[0]); + + /* + * Check for high speed support switch + */ + send_cmd(CMD6, 0x00FFFFF0, &response); + + /* + * Check for dma transfer complete + */ + if (!dma_trans_cmpl()) { + return RES_ERROR; + } + + /* + * SD high speed support check + */ + if (status_data[13]&SD_HS_SUPPORT) { + sd_hs_flag=1; + } + + /* + * Application specific command + */ + send_cmd(CMD55, rca << 16, &response); + + /* + * Clear card detect pull-up + */ + send_cmd(ACMD42, 0, &response); + + if (sd_4bit_flag) { + /* + * Application specific command + */ + send_cmd(CMD55, rca << 16, &response); + + /* + * Set data bus width to 4-bit + */ + send_cmd(ACMD6, 2, &response); + + /* + * Enable 4bit mode in controller + */ + regval = sd_in16(SD_HOST_CTRL_R); + regval |= SD_HOST_4BIT; + sd_out16(SD_HOST_CTRL_R, regval); + } + + if (sd_hs_flag) { + /* + * Set adma2 for transfer + */ + setup_adma2_trans(&status_data[0]); + + /* + * Switch device to high speed + */ + send_cmd(CMD6, 0x80FFFFF1, &response); + + /* + * Check for DMA transfer complete + */ + if (!dma_trans_cmpl()) { + return RES_ERROR; + } + + /* + * Disable SD clock and internal clock + */ + regval = sd_in16(SD_CLK_CTL_R); + regval &= ~(SD_CLK_SD_EN|SD_CLK_INT_EN); + sd_out16(SD_CLK_CTL_R, regval); + + clk_div = (SDIO_FREQ/SD_CLK_50M); + if (!(SDIO_FREQ%SD_CLK_50M)) { + clk_div -=1; + } + + /* + * Enable Internal clock and wait for it to stabilize + */ + regval = (clk_div << SD_DIV_SHIFT) | SD_CLK_INT_EN; + sd_out16(SD_CLK_CTL_R, regval); + do { + regval = sd_in16(SD_CLK_CTL_R); + } while (!(regval & SD_CLK_INT_STABLE)); + + /* + * Enable SD clock + */ + regval |= SD_CLK_SD_EN; + sd_out16(SD_CLK_CTL_R, regval); + + /* + * Enable high speed mode in controller + */ + regval = sd_in16(SD_HOST_CTRL_R); + regval |= SD_HOST_HS; + sd_out16(SD_HOST_CTRL_R, regval); + } else { + /* + * Disable SD clock and internal clock + */ + regval = sd_in16(SD_CLK_CTL_R); + regval &= ~(SD_CLK_SD_EN|SD_CLK_INT_EN); + sd_out16(SD_CLK_CTL_R, regval); + + /* + * Calculating clock divisor + */ + clk_div = (SDIO_FREQ/SD_CLK_25M); + if (!(SDIO_FREQ%SD_CLK_25M)) { + clk_div -=1; + } + + /* + * Enable Internal clock and wait for it to stabilize + */ + regval = (clk_div << SD_DIV_SHIFT) | SD_CLK_INT_EN; + sd_out16(SD_CLK_CTL_R, regval); + do { + regval = sd_in16(SD_CLK_CTL_R); + } while (!(regval & SD_CLK_INT_STABLE)); + + /* + * Enable SD clock + */ + regval |= SD_CLK_SD_EN; + sd_out16(SD_CLK_CTL_R, regval); + } + + /* + * Set R/W block length to 512 + */ + send_cmd(CMD16, SD_BLOCK_SZ, &response); + +fail: + CardType = ty; + + return RES_OK; +} +#endif + +#endif diff --git a/quad/xsdk_workspace/zybo_fsbl/src/nand.c b/quad/xsdk_workspace/zybo_fsbl/src/nand.c new file mode 100644 index 0000000000000000000000000000000000000000..7a50c35bea57061cd536ac5d94ce4aea39206095 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/nand.c @@ -0,0 +1,304 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file nand.c +* +* Contains code for the NAND FLASH functionality. Bad Block management +* is simple: skip the bad blocks and keep going. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 01/10/10 Initial release +* 2.00a mb 25/05/12 fsbl changes for standalone bsp based +* 3.00a sgd 30/01/13 Code cleanup +* 5.00a sgd 17/05/13 Support for Multi Boot +* </pre> +* +* @note +* +******************************************************************************/ + +/***************************** Include Files *********************************/ +#include "xparameters.h" +#include "fsbl.h" +#ifdef XPAR_PS7_NAND_0_BASEADDR +#include "nand.h" +#include "xnandps_bbm.h" + + +/************************** Constant Definitions *****************************/ + +#define NAND_DEVICE_ID XPAR_XNANDPS_0_DEVICE_ID + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ +static u32 XNandPs_CalculateLength(XNandPs *NandInstPtr, + u64 Offset, + u32 Length); + +/************************** Variable Definitions *****************************/ + +extern u32 FlashReadBaseAddress; +extern u32 FlashOffsetAddress; + +XNandPs *NandInstPtr; +XNandPs NandInstance; /* XNand Instance. */ + +/******************************************************************************/ +/** +* +* This function initializes the controller for the NAND FLASH interface. +* +* @param none +* +* @return +* - XST_SUCCESS if the controller initializes correctly +* - XST_FAILURE if the controller fails to initializes correctly +* +* @note none. +* +****************************************************************************/ +u32 InitNand(void) +{ + + u32 Status; + XNandPs_Config *ConfigPtr; + + /* + * Set up pointers to instance and the config structure + */ + NandInstPtr = &NandInstance; + + /* + * Initialize the flash driver. + */ + ConfigPtr = XNandPs_LookupConfig(NAND_DEVICE_ID); + + if (ConfigPtr == NULL) { + fsbl_printf(DEBUG_GENERAL,"Nand Driver failed \n \r"); + return XST_FAILURE; + } + + Status = XNandPs_CfgInitialize(NandInstPtr, ConfigPtr, + ConfigPtr->SmcBase,ConfigPtr->FlashBase); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"NAND intialization failed \n \r"); + return XST_FAILURE; + } + + /* + * Set up base address for access + */ + FlashReadBaseAddress = XPS_NAND_BASEADDR; + + fsbl_printf(DEBUG_INFO,"InitNand: Geometry = 0x%x\r\n", + NandInstPtr->Geometry.FlashWidth); + + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_GENERAL,"InitNand: Status = 0x%.8x\r\n", + Status); + return XST_FAILURE; + } + + /* + * set up the FLASH access pointers + */ + fsbl_printf(DEBUG_INFO,"Nand driver initialized \n\r"); + + return XST_SUCCESS; +} + +/******************************************************************************/ +/** +* +* This function provides the NAND FLASH interface for the Simplified header +* functionality. This function handles bad blocks. +* +* The source address is the absolute good address, bad blocks are skipped +* without incrementing the source address. +* +* @param SourceAddress is address in FLASH data space, absolute good address +* @param DestinationAddress is address in OCM data space +* +* @return XST_SUCCESS if the transfer completes correctly +* XST_FAILURE if the transfer fails to completes correctly +* +* @note none. +* +****************************************************************************/ +u32 NandAccess(u32 SourceAddress, u32 DestinationAddress, u32 LengthBytes) +{ + u32 ActLen; + u32 BlockOffset; + u32 Block; + u32 Status; + u32 BytesLeft = LengthBytes; + u32 BlockSize = NandInstPtr->Geometry.BlockSize; + u8 *BufPtr = (u8 *)DestinationAddress; + u32 ReadLen; + u32 BlockReadLen; + u32 Offset; + u32 TmpAddress = 0 ; + u32 BlockCount = 0; + u32 BadBlocks = 0; + + /* + * First get bad blocks before the source address + */ + while (TmpAddress < SourceAddress) { + while (XNandPs_IsBlockBad(NandInstPtr, BlockCount) == + XST_SUCCESS) { + BlockCount ++; + BadBlocks ++; + } + + TmpAddress += BlockSize; + BlockCount ++; + } + + Offset = SourceAddress + BadBlocks * BlockSize; + + /* + * Calculate the actual length including bad blocks + */ + ActLen = XNandPs_CalculateLength(NandInstPtr, Offset, LengthBytes); + + /* + * Check if the actual length cross flash size + */ + if (Offset + ActLen > NandInstPtr->Geometry.DeviceSize) { + return XST_FAILURE; + } + + while (BytesLeft > 0) { + BlockOffset = Offset & (BlockSize - 1); + Block = (Offset & ~(BlockSize - 1))/BlockSize; + BlockReadLen = BlockSize - BlockOffset; + + Status = XNandPs_IsBlockBad(NandInstPtr, Block); + if (Status == XST_SUCCESS) { + /* Move to next block */ + Offset += BlockReadLen; + continue; + } + + /* + * Check if we cross block boundary + */ + if (BytesLeft < BlockReadLen) { + ReadLen = BytesLeft; + } else { + ReadLen = BlockReadLen; + } + + /* + * Read from the NAND flash + */ + Status = XNandPs_Read(NandInstPtr, Offset, ReadLen, BufPtr, NULL); + if (Status != XST_SUCCESS) { + return Status; + } + BytesLeft -= ReadLen; + Offset += ReadLen; + BufPtr += ReadLen; + } + + return XST_SUCCESS; +} + +/*****************************************************************************/ +/** +* +* This function returns the length including bad blocks from a given offset and +* length. +* +* @param NandInstPtr is the pointer to the XNandPs instance. +* @param Offset is the flash data address to read from. +* @param Length is number of bytes to read. +* +* @return +* - Return actual length including bad blocks. +* +* @note None. +* +******************************************************************************/ +static u32 XNandPs_CalculateLength(XNandPs *NandInstPtr, + u64 Offset, + u32 Length) +{ + u32 BlockSize = NandInstPtr->Geometry.BlockSize; + u32 CurBlockLen; + u32 CurBlock; + u32 Status; + u32 TempLen = 0; + u32 ActLen = 0; + + while (TempLen < Length) { + CurBlockLen = BlockSize - (Offset & (BlockSize - 1)); + CurBlock = (Offset & ~(BlockSize - 1))/BlockSize; + + /* + * Check if the block is bad + */ + Status = XNandPs_IsBlockBad(NandInstPtr, CurBlock); + if (Status != XST_SUCCESS) { + /* Good Block */ + TempLen += CurBlockLen; + } + ActLen += CurBlockLen; + Offset += CurBlockLen; + if (Offset >= NandInstPtr->Geometry.DeviceSize) { + break; + } + } + + return ActLen; +} + +#endif diff --git a/quad/xsdk_workspace/zybo_fsbl/src/nand.h b/quad/xsdk_workspace/zybo_fsbl/src/nand.h new file mode 100644 index 0000000000000000000000000000000000000000..a7bdb08af8284ee66f8bf7b0c8130af0027d25bd --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/nand.h @@ -0,0 +1,101 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file nand.h +* +* This file contains the interface for the NAND FLASH functionality +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 01/10/10 Initial release +* 2.00a mb 30/05/12 added the flag XPAR_PS7_NAND_0_BASEADDR +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___NAND_H___ +#define ___NAND_H___ + + +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ + + +#include "smc.h" + +#ifdef XPAR_PS7_NAND_0_BASEADDR + +#include "xnandps.h" +#include "xnandps_bbm.h" +/**************************** Type Definitions *******************************/ + +/************************** Constant Definitions *****************************/ + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ +u32 InitNand(void); + +u32 NandAccess( u32 SourceAddress, + u32 DestinationAddress, + u32 LengthWords); +#endif +/************************** Variable Definitions *****************************/ + + +#ifdef __cplusplus +} +#endif + + +#endif /* ___NAND_H___ */ + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/nor.c b/quad/xsdk_workspace/zybo_fsbl/src/nor.c new file mode 100644 index 0000000000000000000000000000000000000000..0dc6c14ec5e17ebc15ca7f2a1b69b3a336da9f47 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/nor.c @@ -0,0 +1,153 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file nor.c +* +* Contains code for the NOR FLASH functionality. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 01/10/10 Initial release +* 2.00a mb 25/05/12 mio init removed +* 3.00a sgd 30/01/13 Code cleanup +* +* </pre> +* +* @note +* +******************************************************************************/ + +/***************************** Include Files *********************************/ +#include "fsbl.h" +#include "nor.h" +#include "xstatus.h" + +/************************** Constant Definitions *****************************/ + +/**************************** Type Definitions *******************************/ + + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ + +/************************** Variable Definitions *****************************/ + +extern u32 FlashReadBaseAddress; + +/******************************************************************************/ +/******************************************************************************/ +/** +* +* This function initializes the controller for the NOR FLASH interface. +* +* @param None +* +* @return None +* +* @note None. +* +****************************************************************************/ +void InitNor(void) +{ + + /* + * Set up the base address for access + */ + FlashReadBaseAddress = XPS_NOR_BASEADDR; +} + +/******************************************************************************/ +/** +* +* This function provides the NOR FLASH interface for the Simplified header +* functionality. +* +* @param SourceAddress is address in FLASH data space +* @param DestinationAddress is address in OCM data space +* @param LengthBytes is the data length to transfer in bytes +* +* @return +* - XST_SUCCESS if the write completes correctly +* - XST_FAILURE if the write fails to completes correctly +* +* @note None. +* +****************************************************************************/ +u32 NorAccess(u32 SourceAddress, u32 DestinationAddress, u32 LengthBytes) +{ + u32 Data; + u32 Count; + u32 *SourceAddr; + u32 *DestAddr; + u32 LengthWords; + + /* + * check for non-word tail + * add bytes to cover the end + */ + if ((LengthBytes%4) != 0){ + + LengthBytes += (4 - (LengthBytes & 0x00000003)); + } + + LengthWords = LengthBytes >> WORD_LENGTH_SHIFT; + + SourceAddr = (u32 *)(SourceAddress + FlashReadBaseAddress); + DestAddr = (u32 *)(DestinationAddress); + + /* + * Word transfers, endianism isn't an issue + */ + for (Count=0; Count < LengthWords; Count++){ + + Data = Xil_In32((u32)(SourceAddr++)); + Xil_Out32((u32)(DestAddr++), Data); + } + + return XST_SUCCESS; +} + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/nor.h b/quad/xsdk_workspace/zybo_fsbl/src/nor.h new file mode 100644 index 0000000000000000000000000000000000000000..8e5fe0b6ab1f05225e0f9632b10f5c6419cc64c5 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/nor.h @@ -0,0 +1,98 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file nor.h +* +* This file contains the interface for the NOR FLASH functionality +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 01/10/10 Initial release +* +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___NOR_H___ +#define ___NOR_H___ + + +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ + + +#include "smc.h" + +/************************** Constant Definitions *****************************/ + +#define XPS_NOR_BASEADDR XPS_PARPORT0_BASEADDR + +/**************************** Type Definitions *******************************/ + + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ + + +void InitNor(void); + +u32 NorAccess( u32 SourceAddress, + u32 DestinationAddress, + u32 LengthBytes); + +/************************** Variable Definitions *****************************/ +#ifdef __cplusplus +} +#endif + + +#endif /* ___NOR_H___ */ + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/pcap.c b/quad/xsdk_workspace/zybo_fsbl/src/pcap.c new file mode 100644 index 0000000000000000000000000000000000000000..50bebab3829103dfdc8ae08aa1284a5c00dcf4f3 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/pcap.c @@ -0,0 +1,655 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file pcap.c +* +* Contains code for enabling and accessing the PCAP +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 02/10/10 Initial release +* 2.00a jz 05/28/11 Add SD support +* 2.00a mb 25/05/12 using the EDK provided devcfg driver +* Nand/SD encryption and review comments +* 3.00a mb 16/08/12 Added the poll function +* Removed the FPGA_RST_CTRL define +* Added the flag for NON PS instantiated bitstream +* 4.00a sgd 02/28/13 Fix for CR#681014 - ECC init in FSBL should not call +* fabric_init() +* Fix for CR#689026 - FSBL doesn't hold PL resets active +* during bit download +* Fix for CR#699475 - FSBL functionality is broken and +* its not able to boot in QSPI/NAND +* bootmode +* Fix for CR#705664 - FSBL fails to decrypt the +* bitstream when the image is AES +* encrypted using non-zero key value +* 6.00a kc 08/30/13 Fix for CR#722979 - Provide customer-friendly +* changelogs in FSBL +* +* </pre> +* +* @note +* +******************************************************************************/ + +/***************************** Include Files *********************************/ + +#include "pcap.h" +#include "nand.h" /* For NAND geometry information */ +#include "fsbl.h" +#include "image_mover.h" /* For MoveImage */ +#include "xparameters.h" +#include "xil_exception.h" +#include "xdevcfg.h" +#include "sleep.h" + +#ifdef XPAR_XWDTPS_0_BASEADDR +#include "xwdtps.h" +#endif +/************************** Constant Definitions *****************************/ +/* + * The following constants map to the XPAR parameters created in the + * xparameters.h file. They are only defined here such that a user can easily + * change all the needed parameters in one place. + */ + +#define DCFG_DEVICE_ID XPAR_XDCFG_0_DEVICE_ID + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ +extern int XDcfgPollDone(u32 MaskValue, u32 MaxCount); + +/************************** Variable Definitions *****************************/ +/* Devcfg driver instance */ +static XDcfg DcfgInstance; +XDcfg *DcfgInstPtr; + +#ifdef XPAR_XWDTPS_0_BASEADDR +extern XWdtPs Watchdog; /* Instance of WatchDog Timer */ +#endif + +/******************************************************************************/ +/** +* +* This function transfer data using PCAP +* +* @param SourceDataPtr is a pointer to where the data is read from +* @param DestinationDataPtr is a pointer to where the data is written to +* @param SourceLength is the length of the data to be moved in words +* @param DestinationLength is the length of the data to be moved in words +* @param SecureTransfer indicated the encryption key location, 0 for +* non-encrypted +* +* @return +* - XST_SUCCESS if the transfer is successful +* - XST_FAILURE if the transfer fails +* +* @note None +* +****************************************************************************/ +u32 PcapDataTransfer(u32 *SourceDataPtr, u32 *DestinationDataPtr, + u32 SourceLength, u32 DestinationLength, u32 SecureTransfer) +{ + u32 Status; + u32 PcapTransferType = XDCFG_CONCURRENT_NONSEC_READ_WRITE; + + /* + * Check for secure transfer + */ + if (SecureTransfer) { + PcapTransferType = XDCFG_CONCURRENT_SECURE_READ_WRITE; + } + +#ifdef FSBL_PERF + XTime tXferCur = 0; + FsblGetGlobalTime(tXferCur); +#endif + + /* + * Clear the PCAP status registers + */ + Status = ClearPcapStatus(); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"PCAP_CLEAR_STATUS_FAIL \r\n"); + return XST_FAILURE; + } + +#ifdef XPAR_XWDTPS_0_BASEADDR + /* + * Prevent WDT reset + */ + XWdtPs_RestartWdt(&Watchdog); +#endif + + /* + * PCAP single DMA transfer setup + */ + SourceDataPtr = (u32*)((u32)SourceDataPtr | PCAP_LAST_TRANSFER); + DestinationDataPtr = (u32*)((u32)DestinationDataPtr | PCAP_LAST_TRANSFER); + + /* + * Transfer using Device Configuration + */ + Status = XDcfg_Transfer(DcfgInstPtr, (u8 *)SourceDataPtr, + SourceLength, + (u8 *)DestinationDataPtr, + DestinationLength, PcapTransferType); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"Status of XDcfg_Transfer = %d \r \n",Status); + return XST_FAILURE; + } + + /* + * Dump the PCAP registers + */ + PcapDumpRegisters(); + + /* + * Poll for the DMA done + */ + Status = XDcfgPollDone(XDCFG_IXR_DMA_DONE_MASK, MAX_COUNT); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"PCAP_DMA_DONE_FAIL \r\n"); + return XST_FAILURE; + } + + fsbl_printf(DEBUG_INFO,"DMA Done ! \n\r"); + + /* + * For Performance measurement + */ +#ifdef FSBL_PERF + XTime tXferEnd = 0; + fsbl_printf(DEBUG_GENERAL,"Time taken is "); + FsblMeasurePerfTime(tXferCur,tXferEnd); +#endif + + return XST_SUCCESS; +} + + +/******************************************************************************/ +/** +* +* This function loads PL partition using PCAP +* +* @param SourceDataPtr is a pointer to where the data is read from +* @param DestinationDataPtr is a pointer to where the data is written to +* @param SourceLength is the length of the data to be moved in words +* @param DestinationLength is the length of the data to be moved in words +* @param SecureTransfer indicated the encryption key location, 0 for +* non-encrypted +* +* @return +* - XST_SUCCESS if the transfer is successful +* - XST_FAILURE if the transfer fails +* +* @note None +* +****************************************************************************/ +u32 PcapLoadPartition(u32 *SourceDataPtr, u32 *DestinationDataPtr, + u32 SourceLength, u32 DestinationLength, u32 SecureTransfer) +{ + u32 Status; + u32 PcapTransferType = XDCFG_NON_SECURE_PCAP_WRITE; + + /* + * Check for secure transfer + */ + if (SecureTransfer) { + PcapTransferType = XDCFG_SECURE_PCAP_WRITE; + } + +#ifdef FSBL_PERF + XTime tXferCur = 0; + FsblGetGlobalTime(tXferCur); +#endif + + /* + * Clear the PCAP status registers + */ + Status = ClearPcapStatus(); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"PCAP_CLEAR_STATUS_FAIL \r\n"); + return XST_FAILURE; + } + + /* + * For Bitstream case destination address will be 0xFFFFFFFF + */ + DestinationDataPtr = (u32*)XDCFG_DMA_INVALID_ADDRESS; + + /* + * New Bitstream download initialization sequence + */ + FabricInit(); + + +#ifdef XPAR_XWDTPS_0_BASEADDR + /* + * Prevent WDT reset + */ + XWdtPs_RestartWdt(&Watchdog); +#endif + + /* + * PCAP single DMA transfer setup + */ + SourceDataPtr = (u32*)((u32)SourceDataPtr | PCAP_LAST_TRANSFER); + DestinationDataPtr = (u32*)((u32)DestinationDataPtr | PCAP_LAST_TRANSFER); + + /* + * Transfer using Device Configuration + */ + Status = XDcfg_Transfer(DcfgInstPtr, (u8 *)SourceDataPtr, + SourceLength, + (u8 *)DestinationDataPtr, + DestinationLength, PcapTransferType); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"Status of XDcfg_Transfer = %d \r \n",Status); + return XST_FAILURE; + } + + + /* + * Dump the PCAP registers + */ + PcapDumpRegisters(); + + + /* + * Poll for the DMA done + */ + Status = XDcfgPollDone(XDCFG_IXR_DMA_DONE_MASK, MAX_COUNT); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"PCAP_DMA_DONE_FAIL \r\n"); + return XST_FAILURE; + } + + fsbl_printf(DEBUG_INFO,"DMA Done ! \n\r"); + + /* + * Poll for FPGA Done + */ + Status = XDcfgPollDone(XDCFG_IXR_PCFG_DONE_MASK, MAX_COUNT); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO,"PCAP_FPGA_DONE_FAIL\r\n"); + return XST_FAILURE; + } + + fsbl_printf(DEBUG_INFO,"FPGA Done ! \n\r"); + + /* + * For Performance measurement + */ +#ifdef FSBL_PERF + XTime tXferEnd = 0; + fsbl_printf(DEBUG_GENERAL,"Time taken is "); + FsblMeasurePerfTime(tXferCur,tXferEnd); +#endif + + return XST_SUCCESS; +} + +/******************************************************************************/ +/** +* +* This function Initializes the PCAP driver. +* +* @param none +* +* @return +* - XST_SUCCESS if the pcap driver initialization is successful +* - XST_FAILURE if the pcap driver initialization fails +* +* @note none +* +****************************************************************************/ +int InitPcap(void) +{ + XDcfg_Config *ConfigPtr; + int Status = XST_SUCCESS; + DcfgInstPtr = &DcfgInstance; + + /* + * Initialize the Device Configuration Interface driver. + */ + ConfigPtr = XDcfg_LookupConfig(DCFG_DEVICE_ID); + + Status = XDcfg_CfgInitialize(DcfgInstPtr, ConfigPtr, + ConfigPtr->BaseAddr); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO, "XDcfg_CfgInitialize failed \n\r"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + +/******************************************************************************/ +/** +* +* This function programs the Fabric for use. +* +* @param None +* +* @return None +* - XST_SUCCESS if the Fabric initialization is successful +* - XST_FAILURE if the Fabric initialization fails +* @note None +* +****************************************************************************/ +void FabricInit(void) +{ + u32 PcapReg; + u32 StatusReg; + + /* + * Set Level Shifters DT618760 - PS to PL enabling + */ + Xil_Out32(PS_LVL_SHFTR_EN, LVL_PS_PL); + fsbl_printf(DEBUG_INFO,"Level Shifter Value = 0x%x \r\n", + Xil_In32(PS_LVL_SHFTR_EN)); + + /* + * Get DEVCFG controller settings + */ + PcapReg = XDcfg_ReadReg(DcfgInstPtr->Config.BaseAddr, + XDCFG_CTRL_OFFSET); + + /* + * Setting PCFG_PROG_B signal to high + */ + XDcfg_WriteReg(DcfgInstPtr->Config.BaseAddr, XDCFG_CTRL_OFFSET, + (PcapReg | XDCFG_CTRL_PCFG_PROG_B_MASK)); + + /* + * 5msec delay + */ + usleep(5000); + /* + * Setting PCFG_PROG_B signal to low + */ + XDcfg_WriteReg(DcfgInstPtr->Config.BaseAddr, XDCFG_CTRL_OFFSET, + (PcapReg & ~XDCFG_CTRL_PCFG_PROG_B_MASK)); + + /* + * 5msec delay + */ + usleep(5000); + /* + * Polling the PCAP_INIT status for Reset + */ + while(XDcfg_GetStatusRegister(DcfgInstPtr) & + XDCFG_STATUS_PCFG_INIT_MASK); + + /* + * Setting PCFG_PROG_B signal to high + */ + XDcfg_WriteReg(DcfgInstPtr->Config.BaseAddr, XDCFG_CTRL_OFFSET, + (PcapReg | XDCFG_CTRL_PCFG_PROG_B_MASK)); + + /* + * Polling the PCAP_INIT status for Set + */ + while(!(XDcfg_GetStatusRegister(DcfgInstPtr) & + XDCFG_STATUS_PCFG_INIT_MASK)); + + /* + * Get Device configuration status + */ + StatusReg = XDcfg_GetStatusRegister(DcfgInstPtr); + fsbl_printf(DEBUG_INFO,"Devcfg Status register = 0x%x \r\n",StatusReg); + + fsbl_printf(DEBUG_INFO,"PCAP:Fabric is Initialized done\r\n"); +} + +/******************************************************************************/ +/** +* +* This function Clears the PCAP status registers. +* +* @param None +* +* @return +* - XST_SUCCESS if the pcap status registers are cleared +* - XST_FAILURE if errors are there +* - XST_DEVICE_BUSY if Pcap device is busy +* @note None +* +****************************************************************************/ +u32 ClearPcapStatus(void) +{ + + u32 StatusReg; + u32 IntStatusReg; + + /* + * Clear it all, so if Boot ROM comes back, it can proceed + */ + XDcfg_IntrClear(DcfgInstPtr, 0xFFFFFFFF); + + /* + * Get PCAP Interrupt Status Register + */ + IntStatusReg = XDcfg_IntrGetStatus(DcfgInstPtr); + if (IntStatusReg & FSBL_XDCFG_IXR_ERROR_FLAGS_MASK) { + fsbl_printf(DEBUG_INFO,"FATAL errors in PCAP %x\r\n", + IntStatusReg); + return XST_FAILURE; + } + + /* + * Read the PCAP status register for DMA status + */ + StatusReg = XDcfg_GetStatusRegister(DcfgInstPtr); + + fsbl_printf(DEBUG_INFO,"PCAP:StatusReg = 0x%.8x\r\n", StatusReg); + + /* + * If the queue is full, return w/ XST_DEVICE_BUSY + */ + if ((StatusReg & XDCFG_STATUS_DMA_CMD_Q_F_MASK) == + XDCFG_STATUS_DMA_CMD_Q_F_MASK) { + + fsbl_printf(DEBUG_INFO,"PCAP_DEVICE_BUSY\r\n"); + return XST_DEVICE_BUSY; + } + + fsbl_printf(DEBUG_INFO,"PCAP:device ready\r\n"); + + /* + * There are unacknowledged DMA commands outstanding + */ + if ((StatusReg & XDCFG_STATUS_DMA_CMD_Q_E_MASK) != + XDCFG_STATUS_DMA_CMD_Q_E_MASK) { + + IntStatusReg = XDcfg_IntrGetStatus(DcfgInstPtr); + + if ((IntStatusReg & XDCFG_IXR_DMA_DONE_MASK) != + XDCFG_IXR_DMA_DONE_MASK){ + /* + * Error state, transfer cannot occur + */ + fsbl_printf(DEBUG_INFO,"PCAP:IntStatus indicates error\r\n"); + return XST_FAILURE; + } + else { + /* + * clear out the status + */ + XDcfg_IntrClear(DcfgInstPtr, XDCFG_IXR_DMA_DONE_MASK); + } + } + + if ((StatusReg & XDCFG_STATUS_DMA_DONE_CNT_MASK) != 0) { + XDcfg_IntrClear(DcfgInstPtr, StatusReg & + XDCFG_STATUS_DMA_DONE_CNT_MASK); + } + + fsbl_printf(DEBUG_INFO,"PCAP:Clear done\r\n"); + + return XST_SUCCESS; +} + +/******************************************************************************/ +/** +* +* This function prints PCAP register status. +* +* @param none +* +* @return none +* +* @note none +* +****************************************************************************/ +void PcapDumpRegisters (void) { + + fsbl_printf(DEBUG_INFO,"PCAP register dump:\r\n"); + + fsbl_printf(DEBUG_INFO,"PCAP CTRL 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_CTRL_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_CTRL_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP LOCK 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_LOCK_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_LOCK_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP CONFIG 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_CFG_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_CFG_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP ISR 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_INT_STS_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_INT_STS_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP IMR 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_INT_MASK_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_INT_MASK_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP STATUS 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_STATUS_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_STATUS_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP DMA SRC ADDR 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_SRC_ADDR_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_SRC_ADDR_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP DMA DEST ADDR 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_DEST_ADDR_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_DEST_ADDR_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP DMA SRC LEN 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_SRC_LEN_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_SRC_LEN_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP DMA DEST LEN 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_DEST_LEN_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_DMA_DEST_LEN_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP ROM SHADOW CTRL 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_ROM_SHADOW_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_ROM_SHADOW_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP MBOOT 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_MULTIBOOT_ADDR_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_MULTIBOOT_ADDR_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP SW ID 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_SW_ID_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_SW_ID_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP UNLOCK 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_UNLOCK_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_UNLOCK_OFFSET)); + fsbl_printf(DEBUG_INFO,"PCAP MCTRL 0x%x: 0x%08x\r\n", + XPS_DEV_CFG_APB_BASEADDR + XDCFG_MCTRL_OFFSET, + Xil_In32(XPS_DEV_CFG_APB_BASEADDR + XDCFG_MCTRL_OFFSET)); +} + +/******************************************************************************/ +/** +* +* This function Polls for the DMA done or FPGA done. +* +* @param none +* +* @return +* - XST_SUCCESS if polling for DMA/FPGA done is successful +* - XST_FAILURE if polling for DMA/FPGA done fails +* +* @note none +* +****************************************************************************/ +int XDcfgPollDone(u32 MaskValue, u32 MaxCount) +{ + int Count = MaxCount; + u32 IntrStsReg = 0; + + /* + * poll for the DMA done + */ + IntrStsReg = XDcfg_IntrGetStatus(DcfgInstPtr); + while ((IntrStsReg & MaskValue) != + MaskValue) { + IntrStsReg = XDcfg_IntrGetStatus(DcfgInstPtr); + Count -=1; + + if (IntrStsReg & FSBL_XDCFG_IXR_ERROR_FLAGS_MASK) { + fsbl_printf(DEBUG_INFO,"FATAL errors in PCAP %x\r\n", + IntrStsReg); + PcapDumpRegisters(); + return XST_FAILURE; + } + + if(!Count) { + fsbl_printf(DEBUG_GENERAL,"PCAP transfer timed out \r\n"); + return XST_FAILURE; + } + if (Count > (MAX_COUNT-100)) { + fsbl_printf(DEBUG_GENERAL,"."); + } + } + + fsbl_printf(DEBUG_GENERAL,"\n\r"); + + XDcfg_IntrClear(DcfgInstPtr, IntrStsReg & MaskValue); + + return XST_SUCCESS; +} + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/pcap.h b/quad/xsdk_workspace/zybo_fsbl/src/pcap.h new file mode 100644 index 0000000000000000000000000000000000000000..b0242d78fb5e2783921a263de06af9f71829985c --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/pcap.h @@ -0,0 +1,110 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file pcap.h +* +* This file contains the interface for intiializing and accessing the PCAP +* +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 02/10/10 Initial release +* 2.00a mb 16/08/12 Added the macros and function prototypes +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___PCAP_H___ +#define ___PCAP_H___ + + +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ +#include "xdevcfg.h" + +/************************** Function Prototypes ******************************/ + + +/* Multiboot register offset mask */ +#define PCAP_MBOOT_REG_REBOOT_OFFSET_MASK 0x1FFF +#define PCAP_CTRL_PCFG_AES_FUSE_EFUSE_MASK 0x1000 + +#define PCAP_LAST_TRANSFER 1 +#define MAX_COUNT 1000000000 +#define LVL_PL_PS 0x0000000F +#define LVL_PS_PL 0x0000000A + +/* Fix for #672779 */ +#define FSBL_XDCFG_IXR_ERROR_FLAGS_MASK (XDCFG_IXR_AXI_WERR_MASK | \ + XDCFG_IXR_AXI_RTO_MASK | \ + XDCFG_IXR_AXI_RERR_MASK | \ + XDCFG_IXR_RX_FIFO_OV_MASK | \ + XDCFG_IXR_DMA_CMD_ERR_MASK |\ + XDCFG_IXR_DMA_Q_OV_MASK | \ + XDCFG_IXR_P2D_LEN_ERR_MASK |\ + XDCFG_IXR_PCFG_HMAC_ERR_MASK) + +int InitPcap(void); +void PcapDumpRegisters(void); +u32 ClearPcapStatus(void); +void FabricInit(void); +int XDcfgPollDone(u32 MaskValue, u32 MaxCount); +u32 PcapLoadPartition(u32 *SourceData, u32 *DestinationData, u32 SourceLength, + u32 DestinationLength, u32 Flags); +u32 PcapDataTransfer(u32 *SourceData, u32 *DestinationData, u32 SourceLength, + u32 DestinationLength, u32 Flags); +/************************** Variable Definitions *****************************/ +#ifdef __cplusplus +} +#endif + + +#endif /* ___PCAP_H___ */ + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.c b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.c new file mode 100644 index 0000000000000000000000000000000000000000..182b94b57bd1df0e3e0ca275aca23631f9375d65 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.c @@ -0,0 +1,12655 @@ + /****************************************************************************** + * + * (c) Copyright 2010-2012 Xilinx, Inc. All rights reserved. + * + * This file contains confidential and proprietary information of Xilinx, Inc. + * and is protected under U.S. and international copyright and other + * intellectual property laws. + * + * DISCLAIMER + * This disclaimer is not a license and does not grant any rights to the + * materials distributed herewith. Except as otherwise provided in a valid + * license issued to you by Xilinx, and to the maximum extent permitted by + * applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE \"AS IS\" AND WITH ALL + * FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, + * IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF + * MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; + * and (2) Xilinx shall not be liable (whether in contract or tort, including + * negligence, or under any other theory of liability) for any loss or damage + * of any kind or nature related to, arising under or in connection with these + * materials, including for any direct, or any indirect, special, incidental, + * or consequential loss or damage (including loss of data, profits, goodwill, + * or any type of loss or damage suffered as a result of any action brought by + * a third party) even if such damage or loss was reasonably foreseeable or + * Xilinx had been advised of the possibility of the same. + * + * CRITICAL APPLICATIONS + * Xilinx products are not designed or intended to be fail-safe, or for use in + * any application requiring fail-safe performance, such as life-support or + * safety devices or systems, Class III medical devices, nuclear facilities, + * applications related to the deployment of airbags, or any other applications + * that could lead to death, personal injury, or severe property or + * environmental damage (individually and collectively, \"Critical + * Applications\"). Customer assumes the sole risk and liability of any use of + * Xilinx products in Critical Applications, subject only to applicable laws + * and regulations governing limitations on product liability. + * + * THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE + * AT ALL TIMES. + * + ******************************************************************************/ + /****************************************************************************/ + /** + * + * @file ps7_init.c + * + * This file is automatically generated + * + *****************************************************************************/ + + #include "ps7_init.h" + +unsigned long ps7_pll_init_data_1_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: PLL SLCR REGISTERS + // .. .. START: ARM PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000110[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000110[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x177 + // .. .. ==> 0XF8000110[21:12] = 0x00000177U + // .. .. ==> MASK : 0x003FF000U VAL : 0x00177000U + // .. .. + EMIT_MASKWRITE(0XF8000110, 0x003FFFF0U ,0x001772C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x1a + // .. .. .. ==> 0XF8000100[18:12] = 0x0000001AU + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x0001A000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x0007F000U ,0x0001A000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000100[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000100[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000100[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. ARM_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000001U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000100[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. .. SRCSEL = 0x0 + // .. .. .. ==> 0XF8000120[5:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. .. .. DIVISOR = 0x2 + // .. .. .. ==> 0XF8000120[13:8] = 0x00000002U + // .. .. .. ==> MASK : 0x00003F00U VAL : 0x00000200U + // .. .. .. CPU_6OR4XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[24:24] = 0x00000001U + // .. .. .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. .. .. CPU_3OR2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[25:25] = 0x00000001U + // .. .. .. ==> MASK : 0x02000000U VAL : 0x02000000U + // .. .. .. CPU_2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[26:26] = 0x00000001U + // .. .. .. ==> MASK : 0x04000000U VAL : 0x04000000U + // .. .. .. CPU_1XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[27:27] = 0x00000001U + // .. .. .. ==> MASK : 0x08000000U VAL : 0x08000000U + // .. .. .. CPU_PERI_CLKACT = 0x1 + // .. .. .. ==> 0XF8000120[28:28] = 0x00000001U + // .. .. .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000120, 0x1F003F30U ,0x1F000200U), + // .. .. FINISH: ARM PLL INIT + // .. .. START: DDR PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000114[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000114[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x1db + // .. .. ==> 0XF8000114[21:12] = 0x000001DBU + // .. .. ==> MASK : 0x003FF000U VAL : 0x001DB000U + // .. .. + EMIT_MASKWRITE(0XF8000114, 0x003FFFF0U ,0x001DB2C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x15 + // .. .. .. ==> 0XF8000104[18:12] = 0x00000015U + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x00015000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x0007F000U ,0x00015000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000104[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000104[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000104[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. DDR_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[1:1] = 0x00000001U + // .. .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000002U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000104[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. .. DDR_3XCLKACT = 0x1 + // .. .. .. ==> 0XF8000124[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. DDR_2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000124[1:1] = 0x00000001U + // .. .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. .. DDR_3XCLK_DIVISOR = 0x2 + // .. .. .. ==> 0XF8000124[25:20] = 0x00000002U + // .. .. .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. .. .. DDR_2XCLK_DIVISOR = 0x3 + // .. .. .. ==> 0XF8000124[31:26] = 0x00000003U + // .. .. .. ==> MASK : 0xFC000000U VAL : 0x0C000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000124, 0xFFF00003U ,0x0C200003U), + // .. .. FINISH: DDR PLL INIT + // .. .. START: IO PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000118[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000118[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x1f4 + // .. .. ==> 0XF8000118[21:12] = 0x000001F4U + // .. .. ==> MASK : 0x003FF000U VAL : 0x001F4000U + // .. .. + EMIT_MASKWRITE(0XF8000118, 0x003FFFF0U ,0x001F42C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x14 + // .. .. .. ==> 0XF8000108[18:12] = 0x00000014U + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x00014000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x0007F000U ,0x00014000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000108[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000108[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000108[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. IO_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[2:2] = 0x00000001U + // .. .. .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000004U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000108[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. FINISH: IO PLL INIT + // .. FINISH: PLL SLCR REGISTERS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_clock_init_data_1_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: CLOCK CONTROL SLCR REGISTERS + // .. CLKACT = 0x1 + // .. ==> 0XF8000128[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. DIVISOR0 = 0x34 + // .. ==> 0XF8000128[13:8] = 0x00000034U + // .. ==> MASK : 0x00003F00U VAL : 0x00003400U + // .. DIVISOR1 = 0x2 + // .. ==> 0XF8000128[25:20] = 0x00000002U + // .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. + EMIT_MASKWRITE(0XF8000128, 0x03F03F01U ,0x00203401U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000138[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000138[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000138, 0x00000011U ,0x00000001U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000140[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000140[6:4] = 0x00000000U + // .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. DIVISOR = 0x8 + // .. ==> 0XF8000140[13:8] = 0x00000008U + // .. ==> MASK : 0x00003F00U VAL : 0x00000800U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000140[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000140, 0x03F03F71U ,0x00100801U), + // .. CLKACT = 0x1 + // .. ==> 0XF800014C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF800014C[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x5 + // .. ==> 0XF800014C[13:8] = 0x00000005U + // .. ==> MASK : 0x00003F00U VAL : 0x00000500U + // .. + EMIT_MASKWRITE(0XF800014C, 0x00003F31U ,0x00000501U), + // .. CLKACT0 = 0x1 + // .. ==> 0XF8000150[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. CLKACT1 = 0x0 + // .. ==> 0XF8000150[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000150[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x14 + // .. ==> 0XF8000150[13:8] = 0x00000014U + // .. ==> MASK : 0x00003F00U VAL : 0x00001400U + // .. + EMIT_MASKWRITE(0XF8000150, 0x00003F33U ,0x00001401U), + // .. CLKACT0 = 0x1 + // .. ==> 0XF8000154[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. CLKACT1 = 0x1 + // .. ==> 0XF8000154[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000154[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x14 + // .. ==> 0XF8000154[13:8] = 0x00000014U + // .. ==> MASK : 0x00003F00U VAL : 0x00001400U + // .. + EMIT_MASKWRITE(0XF8000154, 0x00003F33U ,0x00001403U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000168[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000168[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x5 + // .. ==> 0XF8000168[13:8] = 0x00000005U + // .. ==> MASK : 0x00003F00U VAL : 0x00000500U + // .. + EMIT_MASKWRITE(0XF8000168, 0x00003F31U ,0x00000501U), + // .. SRCSEL = 0x0 + // .. ==> 0XF8000170[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR0 = 0xa + // .. ==> 0XF8000170[13:8] = 0x0000000AU + // .. ==> MASK : 0x00003F00U VAL : 0x00000A00U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000170[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000170, 0x03F03F30U ,0x00100A00U), + // .. SRCSEL = 0x3 + // .. ==> 0XF8000180[5:4] = 0x00000003U + // .. ==> MASK : 0x00000030U VAL : 0x00000030U + // .. DIVISOR0 = 0x6 + // .. ==> 0XF8000180[13:8] = 0x00000006U + // .. ==> MASK : 0x00003F00U VAL : 0x00000600U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000180[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000180, 0x03F03F30U ,0x00100630U), + // .. SRCSEL = 0x2 + // .. ==> 0XF8000190[5:4] = 0x00000002U + // .. ==> MASK : 0x00000030U VAL : 0x00000020U + // .. DIVISOR0 = 0x35 + // .. ==> 0XF8000190[13:8] = 0x00000035U + // .. ==> MASK : 0x00003F00U VAL : 0x00003500U + // .. DIVISOR1 = 0x2 + // .. ==> 0XF8000190[25:20] = 0x00000002U + // .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. + EMIT_MASKWRITE(0XF8000190, 0x03F03F30U ,0x00203520U), + // .. SRCSEL = 0x0 + // .. ==> 0XF80001A0[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR0 = 0xa + // .. ==> 0XF80001A0[13:8] = 0x0000000AU + // .. ==> MASK : 0x00003F00U VAL : 0x00000A00U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF80001A0[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF80001A0, 0x03F03F30U ,0x00100A00U), + // .. CLK_621_TRUE = 0x1 + // .. ==> 0XF80001C4[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XF80001C4, 0x00000001U ,0x00000001U), + // .. DMA_CPU_2XCLKACT = 0x1 + // .. ==> 0XF800012C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. USB0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. USB1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. GEM0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[6:6] = 0x00000001U + // .. ==> MASK : 0x00000040U VAL : 0x00000040U + // .. GEM1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. SDI0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[10:10] = 0x00000001U + // .. ==> MASK : 0x00000400U VAL : 0x00000400U + // .. SDI1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. SPI0_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[14:14] = 0x00000000U + // .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. SPI1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[15:15] = 0x00000000U + // .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. CAN0_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. CAN1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. I2C0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[18:18] = 0x00000001U + // .. ==> MASK : 0x00040000U VAL : 0x00040000U + // .. I2C1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. UART0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[20:20] = 0x00000001U + // .. ==> MASK : 0x00100000U VAL : 0x00100000U + // .. UART1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[21:21] = 0x00000001U + // .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. GPIO_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[22:22] = 0x00000001U + // .. ==> MASK : 0x00400000U VAL : 0x00400000U + // .. LQSPI_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[23:23] = 0x00000001U + // .. ==> MASK : 0x00800000U VAL : 0x00800000U + // .. SMC_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[24:24] = 0x00000001U + // .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. + EMIT_MASKWRITE(0XF800012C, 0x01FFCCCDU ,0x01FC044DU), + // .. FINISH: CLOCK CONTROL SLCR REGISTERS + // .. START: THIS SHOULD BE BLANK + // .. FINISH: THIS SHOULD BE BLANK + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_ddr_init_data_1_0[] = { + // START: top + // .. START: DDR INITIALIZATION + // .. .. START: LOCK DDR + // .. .. reg_ddrc_soft_rstb = 0 + // .. .. ==> 0XF8006000[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_powerdown_en = 0x0 + // .. .. ==> 0XF8006000[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_ddrc_data_bus_width = 0x0 + // .. .. ==> 0XF8006000[3:2] = 0x00000000U + // .. .. ==> MASK : 0x0000000CU VAL : 0x00000000U + // .. .. reg_ddrc_burst8_refresh = 0x0 + // .. .. ==> 0XF8006000[6:4] = 0x00000000U + // .. .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. .. reg_ddrc_rdwr_idle_gap = 0x1 + // .. .. ==> 0XF8006000[13:7] = 0x00000001U + // .. .. ==> MASK : 0x00003F80U VAL : 0x00000080U + // .. .. reg_ddrc_dis_rd_bypass = 0x0 + // .. .. ==> 0XF8006000[14:14] = 0x00000000U + // .. .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_act_bypass = 0x0 + // .. .. ==> 0XF8006000[15:15] = 0x00000000U + // .. .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_auto_refresh = 0x0 + // .. .. ==> 0XF8006000[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006000, 0x0001FFFFU ,0x00000080U), + // .. .. FINISH: LOCK DDR + // .. .. reg_ddrc_t_rfc_nom_x32 = 0x7f + // .. .. ==> 0XF8006004[11:0] = 0x0000007FU + // .. .. ==> MASK : 0x00000FFFU VAL : 0x0000007FU + // .. .. reg_ddrc_active_ranks = 0x1 + // .. .. ==> 0XF8006004[13:12] = 0x00000001U + // .. .. ==> MASK : 0x00003000U VAL : 0x00001000U + // .. .. reg_ddrc_addrmap_cs_bit0 = 0x0 + // .. .. ==> 0XF8006004[18:14] = 0x00000000U + // .. .. ==> MASK : 0x0007C000U VAL : 0x00000000U + // .. .. reg_ddrc_wr_odt_block = 0x1 + // .. .. ==> 0XF8006004[20:19] = 0x00000001U + // .. .. ==> MASK : 0x00180000U VAL : 0x00080000U + // .. .. reg_ddrc_diff_rank_rd_2cycle_gap = 0x0 + // .. .. ==> 0XF8006004[21:21] = 0x00000000U + // .. .. ==> MASK : 0x00200000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_cs_bit1 = 0x0 + // .. .. ==> 0XF8006004[26:22] = 0x00000000U + // .. .. ==> MASK : 0x07C00000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_open_bank = 0x0 + // .. .. ==> 0XF8006004[27:27] = 0x00000000U + // .. .. ==> MASK : 0x08000000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_4bank_ram = 0x0 + // .. .. ==> 0XF8006004[28:28] = 0x00000000U + // .. .. ==> MASK : 0x10000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006004, 0x1FFFFFFFU ,0x0008107FU), + // .. .. reg_ddrc_hpr_min_non_critical_x32 = 0xf + // .. .. ==> 0XF8006008[10:0] = 0x0000000FU + // .. .. ==> MASK : 0x000007FFU VAL : 0x0000000FU + // .. .. reg_ddrc_hpr_max_starve_x32 = 0xf + // .. .. ==> 0XF8006008[21:11] = 0x0000000FU + // .. .. ==> MASK : 0x003FF800U VAL : 0x00007800U + // .. .. reg_ddrc_hpr_xact_run_length = 0xf + // .. .. ==> 0XF8006008[25:22] = 0x0000000FU + // .. .. ==> MASK : 0x03C00000U VAL : 0x03C00000U + // .. .. + EMIT_MASKWRITE(0XF8006008, 0x03FFFFFFU ,0x03C0780FU), + // .. .. reg_ddrc_lpr_min_non_critical_x32 = 0x1 + // .. .. ==> 0XF800600C[10:0] = 0x00000001U + // .. .. ==> MASK : 0x000007FFU VAL : 0x00000001U + // .. .. reg_ddrc_lpr_max_starve_x32 = 0x2 + // .. .. ==> 0XF800600C[21:11] = 0x00000002U + // .. .. ==> MASK : 0x003FF800U VAL : 0x00001000U + // .. .. reg_ddrc_lpr_xact_run_length = 0x8 + // .. .. ==> 0XF800600C[25:22] = 0x00000008U + // .. .. ==> MASK : 0x03C00000U VAL : 0x02000000U + // .. .. + EMIT_MASKWRITE(0XF800600C, 0x03FFFFFFU ,0x02001001U), + // .. .. reg_ddrc_w_min_non_critical_x32 = 0x1 + // .. .. ==> 0XF8006010[10:0] = 0x00000001U + // .. .. ==> MASK : 0x000007FFU VAL : 0x00000001U + // .. .. reg_ddrc_w_xact_run_length = 0x8 + // .. .. ==> 0XF8006010[14:11] = 0x00000008U + // .. .. ==> MASK : 0x00007800U VAL : 0x00004000U + // .. .. reg_ddrc_w_max_starve_x32 = 0x2 + // .. .. ==> 0XF8006010[25:15] = 0x00000002U + // .. .. ==> MASK : 0x03FF8000U VAL : 0x00010000U + // .. .. + EMIT_MASKWRITE(0XF8006010, 0x03FFFFFFU ,0x00014001U), + // .. .. reg_ddrc_t_rc = 0x1a + // .. .. ==> 0XF8006014[5:0] = 0x0000001AU + // .. .. ==> MASK : 0x0000003FU VAL : 0x0000001AU + // .. .. reg_ddrc_t_rfc_min = 0x54 + // .. .. ==> 0XF8006014[13:6] = 0x00000054U + // .. .. ==> MASK : 0x00003FC0U VAL : 0x00001500U + // .. .. reg_ddrc_post_selfref_gap_x32 = 0x10 + // .. .. ==> 0XF8006014[20:14] = 0x00000010U + // .. .. ==> MASK : 0x001FC000U VAL : 0x00040000U + // .. .. + EMIT_MASKWRITE(0XF8006014, 0x001FFFFFU ,0x0004151AU), + // .. .. reg_ddrc_wr2pre = 0x12 + // .. .. ==> 0XF8006018[4:0] = 0x00000012U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000012U + // .. .. reg_ddrc_powerdown_to_x32 = 0x6 + // .. .. ==> 0XF8006018[9:5] = 0x00000006U + // .. .. ==> MASK : 0x000003E0U VAL : 0x000000C0U + // .. .. reg_ddrc_t_faw = 0x15 + // .. .. ==> 0XF8006018[15:10] = 0x00000015U + // .. .. ==> MASK : 0x0000FC00U VAL : 0x00005400U + // .. .. reg_ddrc_t_ras_max = 0x23 + // .. .. ==> 0XF8006018[21:16] = 0x00000023U + // .. .. ==> MASK : 0x003F0000U VAL : 0x00230000U + // .. .. reg_ddrc_t_ras_min = 0x13 + // .. .. ==> 0XF8006018[26:22] = 0x00000013U + // .. .. ==> MASK : 0x07C00000U VAL : 0x04C00000U + // .. .. reg_ddrc_t_cke = 0x4 + // .. .. ==> 0XF8006018[31:28] = 0x00000004U + // .. .. ==> MASK : 0xF0000000U VAL : 0x40000000U + // .. .. + EMIT_MASKWRITE(0XF8006018, 0xF7FFFFFFU ,0x44E354D2U), + // .. .. reg_ddrc_write_latency = 0x5 + // .. .. ==> 0XF800601C[4:0] = 0x00000005U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000005U + // .. .. reg_ddrc_rd2wr = 0x7 + // .. .. ==> 0XF800601C[9:5] = 0x00000007U + // .. .. ==> MASK : 0x000003E0U VAL : 0x000000E0U + // .. .. reg_ddrc_wr2rd = 0xe + // .. .. ==> 0XF800601C[14:10] = 0x0000000EU + // .. .. ==> MASK : 0x00007C00U VAL : 0x00003800U + // .. .. reg_ddrc_t_xp = 0x4 + // .. .. ==> 0XF800601C[19:15] = 0x00000004U + // .. .. ==> MASK : 0x000F8000U VAL : 0x00020000U + // .. .. reg_ddrc_pad_pd = 0x0 + // .. .. ==> 0XF800601C[22:20] = 0x00000000U + // .. .. ==> MASK : 0x00700000U VAL : 0x00000000U + // .. .. reg_ddrc_rd2pre = 0x4 + // .. .. ==> 0XF800601C[27:23] = 0x00000004U + // .. .. ==> MASK : 0x0F800000U VAL : 0x02000000U + // .. .. reg_ddrc_t_rcd = 0x7 + // .. .. ==> 0XF800601C[31:28] = 0x00000007U + // .. .. ==> MASK : 0xF0000000U VAL : 0x70000000U + // .. .. + EMIT_MASKWRITE(0XF800601C, 0xFFFFFFFFU ,0x720238E5U), + // .. .. reg_ddrc_t_ccd = 0x4 + // .. .. ==> 0XF8006020[4:2] = 0x00000004U + // .. .. ==> MASK : 0x0000001CU VAL : 0x00000010U + // .. .. reg_ddrc_t_rrd = 0x6 + // .. .. ==> 0XF8006020[7:5] = 0x00000006U + // .. .. ==> MASK : 0x000000E0U VAL : 0x000000C0U + // .. .. reg_ddrc_refresh_margin = 0x2 + // .. .. ==> 0XF8006020[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. reg_ddrc_t_rp = 0x7 + // .. .. ==> 0XF8006020[15:12] = 0x00000007U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00007000U + // .. .. reg_ddrc_refresh_to_x32 = 0x8 + // .. .. ==> 0XF8006020[20:16] = 0x00000008U + // .. .. ==> MASK : 0x001F0000U VAL : 0x00080000U + // .. .. reg_ddrc_sdram = 0x1 + // .. .. ==> 0XF8006020[21:21] = 0x00000001U + // .. .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. .. reg_ddrc_mobile = 0x0 + // .. .. ==> 0XF8006020[22:22] = 0x00000000U + // .. .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. .. reg_ddrc_clock_stop_en = 0x0 + // .. .. ==> 0XF8006020[23:23] = 0x00000000U + // .. .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. .. reg_ddrc_read_latency = 0x7 + // .. .. ==> 0XF8006020[28:24] = 0x00000007U + // .. .. ==> MASK : 0x1F000000U VAL : 0x07000000U + // .. .. reg_phy_mode_ddr1_ddr2 = 0x1 + // .. .. ==> 0XF8006020[29:29] = 0x00000001U + // .. .. ==> MASK : 0x20000000U VAL : 0x20000000U + // .. .. reg_ddrc_dis_pad_pd = 0x0 + // .. .. ==> 0XF8006020[30:30] = 0x00000000U + // .. .. ==> MASK : 0x40000000U VAL : 0x00000000U + // .. .. reg_ddrc_loopback = 0x0 + // .. .. ==> 0XF8006020[31:31] = 0x00000000U + // .. .. ==> MASK : 0x80000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006020, 0xFFFFFFFCU ,0x272872D0U), + // .. .. reg_ddrc_en_2t_timing_mode = 0x0 + // .. .. ==> 0XF8006024[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_prefer_write = 0x0 + // .. .. ==> 0XF8006024[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_ddrc_max_rank_rd = 0xf + // .. .. ==> 0XF8006024[5:2] = 0x0000000FU + // .. .. ==> MASK : 0x0000003CU VAL : 0x0000003CU + // .. .. reg_ddrc_mr_wr = 0x0 + // .. .. ==> 0XF8006024[6:6] = 0x00000000U + // .. .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. .. reg_ddrc_mr_addr = 0x0 + // .. .. ==> 0XF8006024[8:7] = 0x00000000U + // .. .. ==> MASK : 0x00000180U VAL : 0x00000000U + // .. .. reg_ddrc_mr_data = 0x0 + // .. .. ==> 0XF8006024[24:9] = 0x00000000U + // .. .. ==> MASK : 0x01FFFE00U VAL : 0x00000000U + // .. .. ddrc_reg_mr_wr_busy = 0x0 + // .. .. ==> 0XF8006024[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. reg_ddrc_mr_type = 0x0 + // .. .. ==> 0XF8006024[26:26] = 0x00000000U + // .. .. ==> MASK : 0x04000000U VAL : 0x00000000U + // .. .. reg_ddrc_mr_rdata_valid = 0x0 + // .. .. ==> 0XF8006024[27:27] = 0x00000000U + // .. .. ==> MASK : 0x08000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006024, 0x0FFFFFFFU ,0x0000003CU), + // .. .. reg_ddrc_final_wait_x32 = 0x7 + // .. .. ==> 0XF8006028[6:0] = 0x00000007U + // .. .. ==> MASK : 0x0000007FU VAL : 0x00000007U + // .. .. reg_ddrc_pre_ocd_x32 = 0x0 + // .. .. ==> 0XF8006028[10:7] = 0x00000000U + // .. .. ==> MASK : 0x00000780U VAL : 0x00000000U + // .. .. reg_ddrc_t_mrd = 0x4 + // .. .. ==> 0XF8006028[13:11] = 0x00000004U + // .. .. ==> MASK : 0x00003800U VAL : 0x00002000U + // .. .. + EMIT_MASKWRITE(0XF8006028, 0x00003FFFU ,0x00002007U), + // .. .. reg_ddrc_emr2 = 0x8 + // .. .. ==> 0XF800602C[15:0] = 0x00000008U + // .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000008U + // .. .. reg_ddrc_emr3 = 0x0 + // .. .. ==> 0XF800602C[31:16] = 0x00000000U + // .. .. ==> MASK : 0xFFFF0000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800602C, 0xFFFFFFFFU ,0x00000008U), + // .. .. reg_ddrc_mr = 0x930 + // .. .. ==> 0XF8006030[15:0] = 0x00000930U + // .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000930U + // .. .. reg_ddrc_emr = 0x4 + // .. .. ==> 0XF8006030[31:16] = 0x00000004U + // .. .. ==> MASK : 0xFFFF0000U VAL : 0x00040000U + // .. .. + EMIT_MASKWRITE(0XF8006030, 0xFFFFFFFFU ,0x00040930U), + // .. .. reg_ddrc_burst_rdwr = 0x4 + // .. .. ==> 0XF8006034[3:0] = 0x00000004U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000004U + // .. .. reg_ddrc_pre_cke_x1024 = 0x101 + // .. .. ==> 0XF8006034[13:4] = 0x00000101U + // .. .. ==> MASK : 0x00003FF0U VAL : 0x00001010U + // .. .. reg_ddrc_post_cke_x1024 = 0x1 + // .. .. ==> 0XF8006034[25:16] = 0x00000001U + // .. .. ==> MASK : 0x03FF0000U VAL : 0x00010000U + // .. .. reg_ddrc_burstchop = 0x0 + // .. .. ==> 0XF8006034[28:28] = 0x00000000U + // .. .. ==> MASK : 0x10000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006034, 0x13FF3FFFU ,0x00011014U), + // .. .. reg_ddrc_force_low_pri_n = 0x0 + // .. .. ==> 0XF8006038[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_dis_dq = 0x0 + // .. .. ==> 0XF8006038[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_phy_debug_mode = 0x0 + // .. .. ==> 0XF8006038[6:6] = 0x00000000U + // .. .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. .. reg_phy_wr_level_start = 0x0 + // .. .. ==> 0XF8006038[7:7] = 0x00000000U + // .. .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. .. reg_phy_rd_level_start = 0x0 + // .. .. ==> 0XF8006038[8:8] = 0x00000000U + // .. .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. .. reg_phy_dq0_wait_t = 0x0 + // .. .. ==> 0XF8006038[12:9] = 0x00000000U + // .. .. ==> MASK : 0x00001E00U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006038, 0x00001FC3U ,0x00000000U), + // .. .. reg_ddrc_addrmap_bank_b0 = 0x7 + // .. .. ==> 0XF800603C[3:0] = 0x00000007U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000007U + // .. .. reg_ddrc_addrmap_bank_b1 = 0x7 + // .. .. ==> 0XF800603C[7:4] = 0x00000007U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000070U + // .. .. reg_ddrc_addrmap_bank_b2 = 0x7 + // .. .. ==> 0XF800603C[11:8] = 0x00000007U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000700U + // .. .. reg_ddrc_addrmap_col_b5 = 0x0 + // .. .. ==> 0XF800603C[15:12] = 0x00000000U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b6 = 0x0 + // .. .. ==> 0XF800603C[19:16] = 0x00000000U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800603C, 0x000FFFFFU ,0x00000777U), + // .. .. reg_ddrc_addrmap_col_b2 = 0x0 + // .. .. ==> 0XF8006040[3:0] = 0x00000000U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b3 = 0x0 + // .. .. ==> 0XF8006040[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b4 = 0x0 + // .. .. ==> 0XF8006040[11:8] = 0x00000000U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b7 = 0x0 + // .. .. ==> 0XF8006040[15:12] = 0x00000000U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b8 = 0x0 + // .. .. ==> 0XF8006040[19:16] = 0x00000000U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b9 = 0xf + // .. .. ==> 0XF8006040[23:20] = 0x0000000FU + // .. .. ==> MASK : 0x00F00000U VAL : 0x00F00000U + // .. .. reg_ddrc_addrmap_col_b10 = 0xf + // .. .. ==> 0XF8006040[27:24] = 0x0000000FU + // .. .. ==> MASK : 0x0F000000U VAL : 0x0F000000U + // .. .. reg_ddrc_addrmap_col_b11 = 0xf + // .. .. ==> 0XF8006040[31:28] = 0x0000000FU + // .. .. ==> MASK : 0xF0000000U VAL : 0xF0000000U + // .. .. + EMIT_MASKWRITE(0XF8006040, 0xFFFFFFFFU ,0xFFF00000U), + // .. .. reg_ddrc_addrmap_row_b0 = 0x6 + // .. .. ==> 0XF8006044[3:0] = 0x00000006U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000006U + // .. .. reg_ddrc_addrmap_row_b1 = 0x6 + // .. .. ==> 0XF8006044[7:4] = 0x00000006U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000060U + // .. .. reg_ddrc_addrmap_row_b2_11 = 0x6 + // .. .. ==> 0XF8006044[11:8] = 0x00000006U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000600U + // .. .. reg_ddrc_addrmap_row_b12 = 0x6 + // .. .. ==> 0XF8006044[15:12] = 0x00000006U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00006000U + // .. .. reg_ddrc_addrmap_row_b13 = 0x6 + // .. .. ==> 0XF8006044[19:16] = 0x00000006U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00060000U + // .. .. reg_ddrc_addrmap_row_b14 = 0xf + // .. .. ==> 0XF8006044[23:20] = 0x0000000FU + // .. .. ==> MASK : 0x00F00000U VAL : 0x00F00000U + // .. .. reg_ddrc_addrmap_row_b15 = 0xf + // .. .. ==> 0XF8006044[27:24] = 0x0000000FU + // .. .. ==> MASK : 0x0F000000U VAL : 0x0F000000U + // .. .. + EMIT_MASKWRITE(0XF8006044, 0x0FFFFFFFU ,0x0FF66666U), + // .. .. reg_ddrc_rank0_rd_odt = 0x0 + // .. .. ==> 0XF8006048[2:0] = 0x00000000U + // .. .. ==> MASK : 0x00000007U VAL : 0x00000000U + // .. .. reg_ddrc_rank0_wr_odt = 0x1 + // .. .. ==> 0XF8006048[5:3] = 0x00000001U + // .. .. ==> MASK : 0x00000038U VAL : 0x00000008U + // .. .. reg_ddrc_rank1_rd_odt = 0x1 + // .. .. ==> 0XF8006048[8:6] = 0x00000001U + // .. .. ==> MASK : 0x000001C0U VAL : 0x00000040U + // .. .. reg_ddrc_rank1_wr_odt = 0x1 + // .. .. ==> 0XF8006048[11:9] = 0x00000001U + // .. .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. .. reg_phy_rd_local_odt = 0x0 + // .. .. ==> 0XF8006048[13:12] = 0x00000000U + // .. .. ==> MASK : 0x00003000U VAL : 0x00000000U + // .. .. reg_phy_wr_local_odt = 0x3 + // .. .. ==> 0XF8006048[15:14] = 0x00000003U + // .. .. ==> MASK : 0x0000C000U VAL : 0x0000C000U + // .. .. reg_phy_idle_local_odt = 0x3 + // .. .. ==> 0XF8006048[17:16] = 0x00000003U + // .. .. ==> MASK : 0x00030000U VAL : 0x00030000U + // .. .. reg_ddrc_rank2_rd_odt = 0x0 + // .. .. ==> 0XF8006048[20:18] = 0x00000000U + // .. .. ==> MASK : 0x001C0000U VAL : 0x00000000U + // .. .. reg_ddrc_rank2_wr_odt = 0x0 + // .. .. ==> 0XF8006048[23:21] = 0x00000000U + // .. .. ==> MASK : 0x00E00000U VAL : 0x00000000U + // .. .. reg_ddrc_rank3_rd_odt = 0x0 + // .. .. ==> 0XF8006048[26:24] = 0x00000000U + // .. .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. .. reg_ddrc_rank3_wr_odt = 0x0 + // .. .. ==> 0XF8006048[29:27] = 0x00000000U + // .. .. ==> MASK : 0x38000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006048, 0x3FFFFFFFU ,0x0003C248U), + // .. .. reg_phy_rd_cmd_to_data = 0x0 + // .. .. ==> 0XF8006050[3:0] = 0x00000000U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. .. reg_phy_wr_cmd_to_data = 0x0 + // .. .. ==> 0XF8006050[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_phy_rdc_we_to_re_delay = 0x8 + // .. .. ==> 0XF8006050[11:8] = 0x00000008U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000800U + // .. .. reg_phy_rdc_fifo_rst_disable = 0x0 + // .. .. ==> 0XF8006050[15:15] = 0x00000000U + // .. .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. .. reg_phy_use_fixed_re = 0x1 + // .. .. ==> 0XF8006050[16:16] = 0x00000001U + // .. .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. .. reg_phy_rdc_fifo_rst_err_cnt_clr = 0x0 + // .. .. ==> 0XF8006050[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_phy_dis_phy_ctrl_rstn = 0x0 + // .. .. ==> 0XF8006050[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. reg_phy_clk_stall_level = 0x0 + // .. .. ==> 0XF8006050[19:19] = 0x00000000U + // .. .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. .. reg_phy_gatelvl_num_of_dq0 = 0x7 + // .. .. ==> 0XF8006050[27:24] = 0x00000007U + // .. .. ==> MASK : 0x0F000000U VAL : 0x07000000U + // .. .. reg_phy_wrlvl_num_of_dq0 = 0x7 + // .. .. ==> 0XF8006050[31:28] = 0x00000007U + // .. .. ==> MASK : 0xF0000000U VAL : 0x70000000U + // .. .. + EMIT_MASKWRITE(0XF8006050, 0xFF0F8FFFU ,0x77010800U), + // .. .. reg_ddrc_dll_calib_to_min_x1024 = 0x1 + // .. .. ==> 0XF8006058[7:0] = 0x00000001U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000001U + // .. .. reg_ddrc_dll_calib_to_max_x1024 = 0x1 + // .. .. ==> 0XF8006058[15:8] = 0x00000001U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00000100U + // .. .. reg_ddrc_dis_dll_calib = 0x0 + // .. .. ==> 0XF8006058[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006058, 0x0001FFFFU ,0x00000101U), + // .. .. reg_ddrc_rd_odt_delay = 0x3 + // .. .. ==> 0XF800605C[3:0] = 0x00000003U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000003U + // .. .. reg_ddrc_wr_odt_delay = 0x0 + // .. .. ==> 0XF800605C[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_ddrc_rd_odt_hold = 0x0 + // .. .. ==> 0XF800605C[11:8] = 0x00000000U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000000U + // .. .. reg_ddrc_wr_odt_hold = 0x5 + // .. .. ==> 0XF800605C[15:12] = 0x00000005U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00005000U + // .. .. + EMIT_MASKWRITE(0XF800605C, 0x0000FFFFU ,0x00005003U), + // .. .. reg_ddrc_pageclose = 0x0 + // .. .. ==> 0XF8006060[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_lpr_num_entries = 0x1f + // .. .. ==> 0XF8006060[6:1] = 0x0000001FU + // .. .. ==> MASK : 0x0000007EU VAL : 0x0000003EU + // .. .. reg_ddrc_auto_pre_en = 0x0 + // .. .. ==> 0XF8006060[7:7] = 0x00000000U + // .. .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. .. reg_ddrc_refresh_update_level = 0x0 + // .. .. ==> 0XF8006060[8:8] = 0x00000000U + // .. .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. .. reg_ddrc_dis_wc = 0x0 + // .. .. ==> 0XF8006060[9:9] = 0x00000000U + // .. .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. .. reg_ddrc_dis_collision_page_opt = 0x0 + // .. .. ==> 0XF8006060[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_ddrc_selfref_en = 0x0 + // .. .. ==> 0XF8006060[12:12] = 0x00000000U + // .. .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006060, 0x000017FFU ,0x0000003EU), + // .. .. reg_ddrc_go2critical_hysteresis = 0x0 + // .. .. ==> 0XF8006064[12:5] = 0x00000000U + // .. .. ==> MASK : 0x00001FE0U VAL : 0x00000000U + // .. .. reg_arb_go2critical_en = 0x1 + // .. .. ==> 0XF8006064[17:17] = 0x00000001U + // .. .. ==> MASK : 0x00020000U VAL : 0x00020000U + // .. .. + EMIT_MASKWRITE(0XF8006064, 0x00021FE0U ,0x00020000U), + // .. .. reg_ddrc_wrlvl_ww = 0x41 + // .. .. ==> 0XF8006068[7:0] = 0x00000041U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000041U + // .. .. reg_ddrc_rdlvl_rr = 0x41 + // .. .. ==> 0XF8006068[15:8] = 0x00000041U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00004100U + // .. .. reg_ddrc_dfi_t_wlmrd = 0x28 + // .. .. ==> 0XF8006068[25:16] = 0x00000028U + // .. .. ==> MASK : 0x03FF0000U VAL : 0x00280000U + // .. .. + EMIT_MASKWRITE(0XF8006068, 0x03FFFFFFU ,0x00284141U), + // .. .. dfi_t_ctrlupd_interval_min_x1024 = 0x10 + // .. .. ==> 0XF800606C[7:0] = 0x00000010U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000010U + // .. .. dfi_t_ctrlupd_interval_max_x1024 = 0x16 + // .. .. ==> 0XF800606C[15:8] = 0x00000016U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00001600U + // .. .. + EMIT_MASKWRITE(0XF800606C, 0x0000FFFFU ,0x00001610U), + // .. .. refresh_timer0_start_value_x32 = 0x0 + // .. .. ==> 0XF80060A0[11:0] = 0x00000000U + // .. .. ==> MASK : 0x00000FFFU VAL : 0x00000000U + // .. .. refresh_timer1_start_value_x32 = 0x8 + // .. .. ==> 0XF80060A0[23:12] = 0x00000008U + // .. .. ==> MASK : 0x00FFF000U VAL : 0x00008000U + // .. .. + EMIT_MASKWRITE(0XF80060A0, 0x00FFFFFFU ,0x00008000U), + // .. .. reg_ddrc_dis_auto_zq = 0x0 + // .. .. ==> 0XF80060A4[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_ddr3 = 0x1 + // .. .. ==> 0XF80060A4[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. reg_ddrc_t_mod = 0x200 + // .. .. ==> 0XF80060A4[11:2] = 0x00000200U + // .. .. ==> MASK : 0x00000FFCU VAL : 0x00000800U + // .. .. reg_ddrc_t_zq_long_nop = 0x200 + // .. .. ==> 0XF80060A4[21:12] = 0x00000200U + // .. .. ==> MASK : 0x003FF000U VAL : 0x00200000U + // .. .. reg_ddrc_t_zq_short_nop = 0x40 + // .. .. ==> 0XF80060A4[31:22] = 0x00000040U + // .. .. ==> MASK : 0xFFC00000U VAL : 0x10000000U + // .. .. + EMIT_MASKWRITE(0XF80060A4, 0xFFFFFFFFU ,0x10200802U), + // .. .. t_zq_short_interval_x1024 = 0xc845 + // .. .. ==> 0XF80060A8[19:0] = 0x0000C845U + // .. .. ==> MASK : 0x000FFFFFU VAL : 0x0000C845U + // .. .. dram_rstn_x1024 = 0x67 + // .. .. ==> 0XF80060A8[27:20] = 0x00000067U + // .. .. ==> MASK : 0x0FF00000U VAL : 0x06700000U + // .. .. + EMIT_MASKWRITE(0XF80060A8, 0x0FFFFFFFU ,0x0670C845U), + // .. .. deeppowerdown_en = 0x0 + // .. .. ==> 0XF80060AC[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. deeppowerdown_to_x1024 = 0xff + // .. .. ==> 0XF80060AC[8:1] = 0x000000FFU + // .. .. ==> MASK : 0x000001FEU VAL : 0x000001FEU + // .. .. + EMIT_MASKWRITE(0XF80060AC, 0x000001FFU ,0x000001FEU), + // .. .. dfi_wrlvl_max_x1024 = 0xfff + // .. .. ==> 0XF80060B0[11:0] = 0x00000FFFU + // .. .. ==> MASK : 0x00000FFFU VAL : 0x00000FFFU + // .. .. dfi_rdlvl_max_x1024 = 0xfff + // .. .. ==> 0XF80060B0[23:12] = 0x00000FFFU + // .. .. ==> MASK : 0x00FFF000U VAL : 0x00FFF000U + // .. .. ddrc_reg_twrlvl_max_error = 0x0 + // .. .. ==> 0XF80060B0[24:24] = 0x00000000U + // .. .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. .. ddrc_reg_trdlvl_max_error = 0x0 + // .. .. ==> 0XF80060B0[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. reg_ddrc_dfi_wr_level_en = 0x1 + // .. .. ==> 0XF80060B0[26:26] = 0x00000001U + // .. .. ==> MASK : 0x04000000U VAL : 0x04000000U + // .. .. reg_ddrc_dfi_rd_dqs_gate_level = 0x1 + // .. .. ==> 0XF80060B0[27:27] = 0x00000001U + // .. .. ==> MASK : 0x08000000U VAL : 0x08000000U + // .. .. reg_ddrc_dfi_rd_data_eye_train = 0x1 + // .. .. ==> 0XF80060B0[28:28] = 0x00000001U + // .. .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. .. + EMIT_MASKWRITE(0XF80060B0, 0x1FFFFFFFU ,0x1CFFFFFFU), + // .. .. reg_ddrc_2t_delay = 0x0 + // .. .. ==> 0XF80060B4[8:0] = 0x00000000U + // .. .. ==> MASK : 0x000001FFU VAL : 0x00000000U + // .. .. reg_ddrc_skip_ocd = 0x1 + // .. .. ==> 0XF80060B4[9:9] = 0x00000001U + // .. .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. .. reg_ddrc_dis_pre_bypass = 0x0 + // .. .. ==> 0XF80060B4[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80060B4, 0x000007FFU ,0x00000200U), + // .. .. reg_ddrc_dfi_t_rddata_en = 0x6 + // .. .. ==> 0XF80060B8[4:0] = 0x00000006U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000006U + // .. .. reg_ddrc_dfi_t_ctrlup_min = 0x3 + // .. .. ==> 0XF80060B8[14:5] = 0x00000003U + // .. .. ==> MASK : 0x00007FE0U VAL : 0x00000060U + // .. .. reg_ddrc_dfi_t_ctrlup_max = 0x40 + // .. .. ==> 0XF80060B8[24:15] = 0x00000040U + // .. .. ==> MASK : 0x01FF8000U VAL : 0x00200000U + // .. .. + EMIT_MASKWRITE(0XF80060B8, 0x01FFFFFFU ,0x00200066U), + // .. .. Clear_Uncorrectable_DRAM_ECC_error = 1 + // .. .. ==> 0XF80060C4[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. Clear_Correctable_DRAM_ECC_error = 1 + // .. .. ==> 0XF80060C4[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. + EMIT_MASKWRITE(0XF80060C4, 0x00000003U ,0x00000003U), + // .. FINISH: DDR INITIALIZATION + // .. Clear_Uncorrectable_DRAM_ECC_error = 0x0 + // .. ==> 0XF80060C4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. Clear_Correctable_DRAM_ECC_error = 0x0 + // .. ==> 0XF80060C4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060C4, 0x00000003U ,0x00000000U), + // .. CORR_ECC_LOG_VALID = 0x0 + // .. ==> 0XF80060C8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. ECC_CORRECTED_BIT_NUM = 0x0 + // .. ==> 0XF80060C8[7:1] = 0x00000000U + // .. ==> MASK : 0x000000FEU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060C8, 0x000000FFU ,0x00000000U), + // .. UNCORR_ECC_LOG_VALID = 0x0 + // .. ==> 0XF80060DC[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060DC, 0x00000001U ,0x00000000U), + // .. STAT_NUM_CORR_ERR = 0x0 + // .. ==> 0XF80060F0[15:8] = 0x00000000U + // .. ==> MASK : 0x0000FF00U VAL : 0x00000000U + // .. STAT_NUM_UNCORR_ERR = 0x0 + // .. ==> 0XF80060F0[7:0] = 0x00000000U + // .. ==> MASK : 0x000000FFU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060F0, 0x0000FFFFU ,0x00000000U), + // .. reg_ddrc_ecc_mode = 0x0 + // .. ==> 0XF80060F4[2:0] = 0x00000000U + // .. ==> MASK : 0x00000007U VAL : 0x00000000U + // .. reg_ddrc_dis_scrub = 0x1 + // .. ==> 0XF80060F4[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. + EMIT_MASKWRITE(0XF80060F4, 0x0000000FU ,0x00000008U), + // .. reg_phy_dif_on = 0x0 + // .. ==> 0XF8006114[3:0] = 0x00000000U + // .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. reg_phy_dif_off = 0x0 + // .. ==> 0XF8006114[7:4] = 0x00000000U + // .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006114, 0x000000FFU ,0x00000000U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF8006118[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF8006118[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF8006118[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF8006118[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF8006118[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF8006118[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF8006118[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF8006118[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF8006118[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF8006118, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF800611C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF800611C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF800611C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF800611C[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF800611C[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF800611C[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF800611C[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF800611C[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF800611C[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF800611C, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF8006120[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF8006120[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF8006120[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF8006120[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF8006120[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF8006120[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF8006120[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF8006120[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF8006120[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF8006120, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF8006124[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF8006124[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF8006124[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF8006124[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF8006124[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF8006124[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF8006124[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF8006124[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF8006124[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF8006124, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF800612C[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x8f + // .. ==> 0XF800612C[19:10] = 0x0000008FU + // .. ==> MASK : 0x000FFC00U VAL : 0x00023C00U + // .. + EMIT_MASKWRITE(0XF800612C, 0x000FFFFFU ,0x00023C00U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF8006130[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x8a + // .. ==> 0XF8006130[19:10] = 0x0000008AU + // .. ==> MASK : 0x000FFC00U VAL : 0x00022800U + // .. + EMIT_MASKWRITE(0XF8006130, 0x000FFFFFU ,0x00022800U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF8006134[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x8b + // .. ==> 0XF8006134[19:10] = 0x0000008BU + // .. ==> MASK : 0x000FFC00U VAL : 0x00022C00U + // .. + EMIT_MASKWRITE(0XF8006134, 0x000FFFFFU ,0x00022C00U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF8006138[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x92 + // .. ==> 0XF8006138[19:10] = 0x00000092U + // .. ==> MASK : 0x000FFC00U VAL : 0x00024800U + // .. + EMIT_MASKWRITE(0XF8006138, 0x000FFFFFU ,0x00024800U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF8006140[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF8006140[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF8006140[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006140, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF8006144[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF8006144[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF8006144[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006144, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF8006148[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF8006148[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF8006148[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006148, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF800614C[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF800614C[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF800614C[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800614C, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_wr_dqs_slave_ratio = 0x77 + // .. ==> 0XF8006154[9:0] = 0x00000077U + // .. ==> MASK : 0x000003FFU VAL : 0x00000077U + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF8006154[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF8006154[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006154, 0x000FFFFFU ,0x00000077U), + // .. reg_phy_wr_dqs_slave_ratio = 0x7c + // .. ==> 0XF8006158[9:0] = 0x0000007CU + // .. ==> MASK : 0x000003FFU VAL : 0x0000007CU + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF8006158[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF8006158[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006158, 0x000FFFFFU ,0x0000007CU), + // .. reg_phy_wr_dqs_slave_ratio = 0x7c + // .. ==> 0XF800615C[9:0] = 0x0000007CU + // .. ==> MASK : 0x000003FFU VAL : 0x0000007CU + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF800615C[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF800615C[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800615C, 0x000FFFFFU ,0x0000007CU), + // .. reg_phy_wr_dqs_slave_ratio = 0x75 + // .. ==> 0XF8006160[9:0] = 0x00000075U + // .. ==> MASK : 0x000003FFU VAL : 0x00000075U + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF8006160[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF8006160[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006160, 0x000FFFFFU ,0x00000075U), + // .. reg_phy_fifo_we_slave_ratio = 0xe4 + // .. ==> 0XF8006168[10:0] = 0x000000E4U + // .. ==> MASK : 0x000007FFU VAL : 0x000000E4U + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF8006168[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF8006168[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006168, 0x001FFFFFU ,0x000000E4U), + // .. reg_phy_fifo_we_slave_ratio = 0xdf + // .. ==> 0XF800616C[10:0] = 0x000000DFU + // .. ==> MASK : 0x000007FFU VAL : 0x000000DFU + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF800616C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF800616C[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800616C, 0x001FFFFFU ,0x000000DFU), + // .. reg_phy_fifo_we_slave_ratio = 0xe0 + // .. ==> 0XF8006170[10:0] = 0x000000E0U + // .. ==> MASK : 0x000007FFU VAL : 0x000000E0U + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF8006170[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF8006170[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006170, 0x001FFFFFU ,0x000000E0U), + // .. reg_phy_fifo_we_slave_ratio = 0xe7 + // .. ==> 0XF8006174[10:0] = 0x000000E7U + // .. ==> MASK : 0x000007FFU VAL : 0x000000E7U + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF8006174[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF8006174[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006174, 0x001FFFFFU ,0x000000E7U), + // .. reg_phy_wr_data_slave_ratio = 0xb7 + // .. ==> 0XF800617C[9:0] = 0x000000B7U + // .. ==> MASK : 0x000003FFU VAL : 0x000000B7U + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF800617C[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF800617C[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800617C, 0x000FFFFFU ,0x000000B7U), + // .. reg_phy_wr_data_slave_ratio = 0xbc + // .. ==> 0XF8006180[9:0] = 0x000000BCU + // .. ==> MASK : 0x000003FFU VAL : 0x000000BCU + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF8006180[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF8006180[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006180, 0x000FFFFFU ,0x000000BCU), + // .. reg_phy_wr_data_slave_ratio = 0xbc + // .. ==> 0XF8006184[9:0] = 0x000000BCU + // .. ==> MASK : 0x000003FFU VAL : 0x000000BCU + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF8006184[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF8006184[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006184, 0x000FFFFFU ,0x000000BCU), + // .. reg_phy_wr_data_slave_ratio = 0xb5 + // .. ==> 0XF8006188[9:0] = 0x000000B5U + // .. ==> MASK : 0x000003FFU VAL : 0x000000B5U + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF8006188[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF8006188[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006188, 0x000FFFFFU ,0x000000B5U), + // .. reg_phy_loopback = 0x0 + // .. ==> 0XF8006190[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. reg_phy_bl2 = 0x0 + // .. ==> 0XF8006190[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_at_spd_atpg = 0x0 + // .. ==> 0XF8006190[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_bist_enable = 0x0 + // .. ==> 0XF8006190[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_bist_force_err = 0x0 + // .. ==> 0XF8006190[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_bist_mode = 0x0 + // .. ==> 0XF8006190[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. reg_phy_invert_clkout = 0x1 + // .. ==> 0XF8006190[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. reg_phy_all_dq_mpr_rd_resp = 0x0 + // .. ==> 0XF8006190[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. reg_phy_sel_logic = 0x0 + // .. ==> 0XF8006190[9:9] = 0x00000000U + // .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. reg_phy_ctrl_slave_ratio = 0x100 + // .. ==> 0XF8006190[19:10] = 0x00000100U + // .. ==> MASK : 0x000FFC00U VAL : 0x00040000U + // .. reg_phy_ctrl_slave_force = 0x0 + // .. ==> 0XF8006190[20:20] = 0x00000000U + // .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. reg_phy_ctrl_slave_delay = 0x0 + // .. ==> 0XF8006190[27:21] = 0x00000000U + // .. ==> MASK : 0x0FE00000U VAL : 0x00000000U + // .. reg_phy_use_rank0_delays = 0x1 + // .. ==> 0XF8006190[28:28] = 0x00000001U + // .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. reg_phy_lpddr = 0x0 + // .. ==> 0XF8006190[29:29] = 0x00000000U + // .. ==> MASK : 0x20000000U VAL : 0x00000000U + // .. reg_phy_cmd_latency = 0x0 + // .. ==> 0XF8006190[30:30] = 0x00000000U + // .. ==> MASK : 0x40000000U VAL : 0x00000000U + // .. reg_phy_int_lpbk = 0x0 + // .. ==> 0XF8006190[31:31] = 0x00000000U + // .. ==> MASK : 0x80000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006190, 0xFFFFFFFFU ,0x10040080U), + // .. reg_phy_wr_rl_delay = 0x2 + // .. ==> 0XF8006194[4:0] = 0x00000002U + // .. ==> MASK : 0x0000001FU VAL : 0x00000002U + // .. reg_phy_rd_rl_delay = 0x4 + // .. ==> 0XF8006194[9:5] = 0x00000004U + // .. ==> MASK : 0x000003E0U VAL : 0x00000080U + // .. reg_phy_dll_lock_diff = 0xf + // .. ==> 0XF8006194[13:10] = 0x0000000FU + // .. ==> MASK : 0x00003C00U VAL : 0x00003C00U + // .. reg_phy_use_wr_level = 0x1 + // .. ==> 0XF8006194[14:14] = 0x00000001U + // .. ==> MASK : 0x00004000U VAL : 0x00004000U + // .. reg_phy_use_rd_dqs_gate_level = 0x1 + // .. ==> 0XF8006194[15:15] = 0x00000001U + // .. ==> MASK : 0x00008000U VAL : 0x00008000U + // .. reg_phy_use_rd_data_eye_level = 0x1 + // .. ==> 0XF8006194[16:16] = 0x00000001U + // .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. reg_phy_dis_calib_rst = 0x0 + // .. ==> 0XF8006194[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_phy_ctrl_slave_delay = 0x0 + // .. ==> 0XF8006194[19:18] = 0x00000000U + // .. ==> MASK : 0x000C0000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006194, 0x000FFFFFU ,0x0001FC82U), + // .. reg_arb_page_addr_mask = 0x0 + // .. ==> 0XF8006204[31:0] = 0x00000000U + // .. ==> MASK : 0xFFFFFFFFU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006204, 0xFFFFFFFFU ,0x00000000U), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF8006208[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF8006208[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF8006208[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF8006208[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF8006208[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF8006208, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF800620C[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF800620C[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF800620C[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF800620C[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF800620C[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF800620C, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF8006210[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF8006210[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF8006210[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF8006210[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF8006210[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF8006210, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF8006214[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF8006214[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF8006214[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF8006214[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF8006214[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF8006214, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF8006218[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF8006218[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF8006218[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF8006218[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF8006218[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006218, 0x000F03FFU ,0x000003FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF800621C[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF800621C[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF800621C[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF800621C[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF800621C[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800621C, 0x000F03FFU ,0x000003FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF8006220[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF8006220[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF8006220[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF8006220[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF8006220[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006220, 0x000F03FFU ,0x000003FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF8006224[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF8006224[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF8006224[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF8006224[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF8006224[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006224, 0x000F03FFU ,0x000003FFU), + // .. reg_ddrc_lpddr2 = 0x0 + // .. ==> 0XF80062A8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. reg_ddrc_per_bank_refresh = 0x0 + // .. ==> 0XF80062A8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_ddrc_derate_enable = 0x0 + // .. ==> 0XF80062A8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_ddrc_mr4_margin = 0x0 + // .. ==> 0XF80062A8[11:4] = 0x00000000U + // .. ==> MASK : 0x00000FF0U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80062A8, 0x00000FF7U ,0x00000000U), + // .. reg_ddrc_mr4_read_interval = 0x0 + // .. ==> 0XF80062AC[31:0] = 0x00000000U + // .. ==> MASK : 0xFFFFFFFFU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80062AC, 0xFFFFFFFFU ,0x00000000U), + // .. reg_ddrc_min_stable_clock_x1 = 0x5 + // .. ==> 0XF80062B0[3:0] = 0x00000005U + // .. ==> MASK : 0x0000000FU VAL : 0x00000005U + // .. reg_ddrc_idle_after_reset_x32 = 0x12 + // .. ==> 0XF80062B0[11:4] = 0x00000012U + // .. ==> MASK : 0x00000FF0U VAL : 0x00000120U + // .. reg_ddrc_t_mrw = 0x5 + // .. ==> 0XF80062B0[21:12] = 0x00000005U + // .. ==> MASK : 0x003FF000U VAL : 0x00005000U + // .. + EMIT_MASKWRITE(0XF80062B0, 0x003FFFFFU ,0x00005125U), + // .. reg_ddrc_max_auto_init_x1024 = 0xa6 + // .. ==> 0XF80062B4[7:0] = 0x000000A6U + // .. ==> MASK : 0x000000FFU VAL : 0x000000A6U + // .. reg_ddrc_dev_zqinit_x32 = 0x12 + // .. ==> 0XF80062B4[17:8] = 0x00000012U + // .. ==> MASK : 0x0003FF00U VAL : 0x00001200U + // .. + EMIT_MASKWRITE(0XF80062B4, 0x0003FFFFU ,0x000012A6U), + // .. START: POLL ON DCI STATUS + // .. DONE = 1 + // .. ==> 0XF8000B74[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKPOLL(0XF8000B74, 0x00002000U), + // .. FINISH: POLL ON DCI STATUS + // .. START: UNLOCK DDR + // .. reg_ddrc_soft_rstb = 0x1 + // .. ==> 0XF8006000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_ddrc_powerdown_en = 0x0 + // .. ==> 0XF8006000[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_ddrc_data_bus_width = 0x0 + // .. ==> 0XF8006000[3:2] = 0x00000000U + // .. ==> MASK : 0x0000000CU VAL : 0x00000000U + // .. reg_ddrc_burst8_refresh = 0x0 + // .. ==> 0XF8006000[6:4] = 0x00000000U + // .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. reg_ddrc_rdwr_idle_gap = 1 + // .. ==> 0XF8006000[13:7] = 0x00000001U + // .. ==> MASK : 0x00003F80U VAL : 0x00000080U + // .. reg_ddrc_dis_rd_bypass = 0x0 + // .. ==> 0XF8006000[14:14] = 0x00000000U + // .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. reg_ddrc_dis_act_bypass = 0x0 + // .. ==> 0XF8006000[15:15] = 0x00000000U + // .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. reg_ddrc_dis_auto_refresh = 0x0 + // .. ==> 0XF8006000[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006000, 0x0001FFFFU ,0x00000081U), + // .. FINISH: UNLOCK DDR + // .. START: CHECK DDR STATUS + // .. ddrc_reg_operating_mode = 1 + // .. ==> 0XF8006054[2:0] = 0x00000001U + // .. ==> MASK : 0x00000007U VAL : 0x00000001U + // .. + EMIT_MASKPOLL(0XF8006054, 0x00000007U), + // .. FINISH: CHECK DDR STATUS + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_mio_init_data_1_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: OCM REMAPPING + // .. VREF_EN = 0x1 + // .. ==> 0XF8000B00[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. VREF_PULLUP_EN = 0x0 + // .. ==> 0XF8000B00[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. CLK_PULLUP_EN = 0x0 + // .. ==> 0XF8000B00[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. SRSTN_PULLUP_EN = 0x0 + // .. ==> 0XF8000B00[9:9] = 0x00000000U + // .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B00, 0x00000303U ,0x00000001U), + // .. FINISH: OCM REMAPPING + // .. START: DDRIOB SETTINGS + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B40[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B40[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B40[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B40[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCR_TYPE = 0x0 + // .. ==> 0XF8000B40[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B40[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B40[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B40[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B40[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B40, 0x00000FFFU ,0x00000600U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B44[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B44[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B44[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B44[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCR_TYPE = 0x0 + // .. ==> 0XF8000B44[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B44[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B44[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B44[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B44[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B44, 0x00000FFFU ,0x00000600U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B48[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x1 + // .. ==> 0XF8000B48[2:1] = 0x00000001U + // .. ==> MASK : 0x00000006U VAL : 0x00000002U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B48[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B48[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B48[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B48[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B48[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B48[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B48[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B48, 0x00000FFFU ,0x00000672U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B4C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x1 + // .. ==> 0XF8000B4C[2:1] = 0x00000001U + // .. ==> MASK : 0x00000006U VAL : 0x00000002U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B4C[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B4C[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B4C[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B4C[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B4C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B4C[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B4C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B4C, 0x00000FFFU ,0x00000672U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B50[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x2 + // .. ==> 0XF8000B50[2:1] = 0x00000002U + // .. ==> MASK : 0x00000006U VAL : 0x00000004U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B50[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B50[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B50[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B50[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B50[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B50[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B50[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B50, 0x00000FFFU ,0x00000674U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B54[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x2 + // .. ==> 0XF8000B54[2:1] = 0x00000002U + // .. ==> MASK : 0x00000006U VAL : 0x00000004U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B54[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B54[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B54[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B54[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B54[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B54[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B54[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B54, 0x00000FFFU ,0x00000674U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B58[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B58[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B58[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B58[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCR_TYPE = 0x0 + // .. ==> 0XF8000B58[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B58[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B58[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B58[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B58[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B58, 0x00000FFFU ,0x00000600U), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B5C[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B5C[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x1a + // .. ==> 0XF8000B5C[18:14] = 0x0000001AU + // .. ==> MASK : 0x0007C000U VAL : 0x00068000U + // .. SLEW_N = 0x1a + // .. ==> 0XF8000B5C[23:19] = 0x0000001AU + // .. ==> MASK : 0x00F80000U VAL : 0x00D00000U + // .. GTL = 0x0 + // .. ==> 0XF8000B5C[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B5C[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B5C, 0xFFFFFFFFU ,0x00D6861CU), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B60[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B60[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x6 + // .. ==> 0XF8000B60[18:14] = 0x00000006U + // .. ==> MASK : 0x0007C000U VAL : 0x00018000U + // .. SLEW_N = 0x1f + // .. ==> 0XF8000B60[23:19] = 0x0000001FU + // .. ==> MASK : 0x00F80000U VAL : 0x00F80000U + // .. GTL = 0x0 + // .. ==> 0XF8000B60[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B60[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B60, 0xFFFFFFFFU ,0x00F9861CU), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B64[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B64[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x6 + // .. ==> 0XF8000B64[18:14] = 0x00000006U + // .. ==> MASK : 0x0007C000U VAL : 0x00018000U + // .. SLEW_N = 0x1f + // .. ==> 0XF8000B64[23:19] = 0x0000001FU + // .. ==> MASK : 0x00F80000U VAL : 0x00F80000U + // .. GTL = 0x0 + // .. ==> 0XF8000B64[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B64[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B64, 0xFFFFFFFFU ,0x00F9861CU), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B68[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B68[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x1a + // .. ==> 0XF8000B68[18:14] = 0x0000001AU + // .. ==> MASK : 0x0007C000U VAL : 0x00068000U + // .. SLEW_N = 0x1a + // .. ==> 0XF8000B68[23:19] = 0x0000001AU + // .. ==> MASK : 0x00F80000U VAL : 0x00D00000U + // .. GTL = 0x0 + // .. ==> 0XF8000B68[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B68[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B68, 0xFFFFFFFFU ,0x00D6861CU), + // .. VREF_INT_EN = 0x0 + // .. ==> 0XF8000B6C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. VREF_SEL = 0x0 + // .. ==> 0XF8000B6C[4:1] = 0x00000000U + // .. ==> MASK : 0x0000001EU VAL : 0x00000000U + // .. VREF_EXT_EN = 0x3 + // .. ==> 0XF8000B6C[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. VREF_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[8:7] = 0x00000000U + // .. ==> MASK : 0x00000180U VAL : 0x00000000U + // .. REFIO_EN = 0x1 + // .. ==> 0XF8000B6C[9:9] = 0x00000001U + // .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. REFIO_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DRST_B_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. CKE_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[14:14] = 0x00000000U + // .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B6C, 0x000073FFU ,0x00000260U), + // .. .. START: ASSERT RESET + // .. .. RESET = 1 + // .. .. ==> 0XF8000B70[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. VRN_OUT = 0x1 + // .. .. ==> 0XF8000B70[5:5] = 0x00000001U + // .. .. ==> MASK : 0x00000020U VAL : 0x00000020U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x00000021U ,0x00000021U), + // .. .. FINISH: ASSERT RESET + // .. .. START: DEASSERT RESET + // .. .. RESET = 0 + // .. .. ==> 0XF8000B70[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. VRN_OUT = 0x1 + // .. .. ==> 0XF8000B70[5:5] = 0x00000001U + // .. .. ==> MASK : 0x00000020U VAL : 0x00000020U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x00000021U ,0x00000020U), + // .. .. FINISH: DEASSERT RESET + // .. .. RESET = 0x1 + // .. .. ==> 0XF8000B70[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. ENABLE = 0x1 + // .. .. ==> 0XF8000B70[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. VRP_TRI = 0x0 + // .. .. ==> 0XF8000B70[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. VRN_TRI = 0x0 + // .. .. ==> 0XF8000B70[3:3] = 0x00000000U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. .. VRP_OUT = 0x0 + // .. .. ==> 0XF8000B70[4:4] = 0x00000000U + // .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. VRN_OUT = 0x1 + // .. .. ==> 0XF8000B70[5:5] = 0x00000001U + // .. .. ==> MASK : 0x00000020U VAL : 0x00000020U + // .. .. NREF_OPT1 = 0x0 + // .. .. ==> 0XF8000B70[7:6] = 0x00000000U + // .. .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. .. NREF_OPT2 = 0x0 + // .. .. ==> 0XF8000B70[10:8] = 0x00000000U + // .. .. ==> MASK : 0x00000700U VAL : 0x00000000U + // .. .. NREF_OPT4 = 0x1 + // .. .. ==> 0XF8000B70[13:11] = 0x00000001U + // .. .. ==> MASK : 0x00003800U VAL : 0x00000800U + // .. .. PREF_OPT1 = 0x0 + // .. .. ==> 0XF8000B70[16:14] = 0x00000000U + // .. .. ==> MASK : 0x0001C000U VAL : 0x00000000U + // .. .. PREF_OPT2 = 0x0 + // .. .. ==> 0XF8000B70[19:17] = 0x00000000U + // .. .. ==> MASK : 0x000E0000U VAL : 0x00000000U + // .. .. UPDATE_CONTROL = 0x0 + // .. .. ==> 0XF8000B70[20:20] = 0x00000000U + // .. .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. .. INIT_COMPLETE = 0x0 + // .. .. ==> 0XF8000B70[21:21] = 0x00000000U + // .. .. ==> MASK : 0x00200000U VAL : 0x00000000U + // .. .. TST_CLK = 0x0 + // .. .. ==> 0XF8000B70[22:22] = 0x00000000U + // .. .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. .. TST_HLN = 0x0 + // .. .. ==> 0XF8000B70[23:23] = 0x00000000U + // .. .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. .. TST_HLP = 0x0 + // .. .. ==> 0XF8000B70[24:24] = 0x00000000U + // .. .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. .. TST_RST = 0x0 + // .. .. ==> 0XF8000B70[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. INT_DCI_EN = 0x0 + // .. .. ==> 0XF8000B70[26:26] = 0x00000000U + // .. .. ==> MASK : 0x04000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x07FFFFFFU ,0x00000823U), + // .. FINISH: DDRIOB SETTINGS + // .. START: MIO PROGRAMMING + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000700[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000700[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000700[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000700[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000700[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000700[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000700[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000700[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000700[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000700, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000704[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000704[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000704[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000704[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000704[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000704[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000704[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000704[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000704[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000704, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000708[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000708[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000708[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000708[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000708[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000708[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000708[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000708[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000708[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000708, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800070C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF800070C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800070C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800070C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800070C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800070C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF800070C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800070C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800070C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800070C, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000710[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000710[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000710[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000710[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000710[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000710[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000710[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000710[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000710[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000710, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000714[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000714[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000714[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000714[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000714[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000714[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000714[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000714[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000714[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000714, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000718[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000718[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000718[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000718[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000718[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000718[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000718[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000718[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000718[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000718, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800071C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800071C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800071C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800071C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800071C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF800071C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800071C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800071C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800071C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800071C, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000720[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000720[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000720[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000720[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000720[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000720[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000720[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000720[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000720[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000720, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000724[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000724[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000724[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000724[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000724[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000724[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000724[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000724[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000724[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000724, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000728[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000728[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000728[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000728[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000728[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U + // .. Speed = 0 + // .. ==> 0XF8000728[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000728[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 1 + // .. ==> 0XF8000728[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000728[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000728, 0x00003FFFU ,0x00001640U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800072C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800072C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800072C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800072C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF800072C[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U + // .. Speed = 0 + // .. ==> 0XF800072C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800072C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 1 + // .. ==> 0XF800072C[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. DisableRcvr = 0 + // .. ==> 0XF800072C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800072C, 0x00003FFFU ,0x00001640U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000730[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000730[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000730[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000730[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000730[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000730[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000730[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000730[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000730[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000734[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000734[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000734[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000734[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000734[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000734[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000734[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000734[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000734[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000738[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000738[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000738[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000738[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000738[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000738[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000738[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000738[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000738[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000738, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800073C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800073C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800073C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800073C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800073C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF800073C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800073C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800073C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800073C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800073C, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000740[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000740[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000740[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000740[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000740[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000740[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000740[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000740[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000740[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000740, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000744[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000744[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000744[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000744[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000744[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000744[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000744[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000744[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000744[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000744, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000748[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000748[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000748[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000748[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000748[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000748[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000748[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000748[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000748[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000748, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800074C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF800074C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800074C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800074C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800074C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800074C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800074C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800074C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF800074C[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF800074C, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000750[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000750[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000750[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000750[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000750[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000750[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000750[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000750[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000750[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000750, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000754[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000754[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000754[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000754[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000754[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000754[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000754[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000754[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000754[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000754, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000758[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000758[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000758[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000758[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000758[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000758[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000758[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000758[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000758[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000758, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800075C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF800075C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800075C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800075C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800075C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800075C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800075C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800075C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800075C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800075C, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000760[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000760[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000760[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000760[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000760[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000760[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000760[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000760[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000760[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000760, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000764[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000764[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000764[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000764[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000764[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000764[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000764[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000764[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000764[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000764, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000768[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000768[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000768[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000768[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000768[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000768[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000768[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000768[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000768[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000768, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800076C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF800076C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800076C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800076C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800076C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800076C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800076C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800076C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800076C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800076C, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000770[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000770[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000770[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000770[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000770[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000770[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000770[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000770[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000770[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000770, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000774[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF8000774[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000774[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000774[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000774[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000774[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000774[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000774[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000774[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000774, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000778[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000778[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000778[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000778[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000778[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000778[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000778[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000778[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000778[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000778, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800077C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF800077C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800077C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800077C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800077C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800077C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800077C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800077C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800077C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800077C, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000780[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000780[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000780[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000780[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000780[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000780[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000780[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000780[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000780[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000780, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000784[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000784[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000784[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000784[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000784[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000784[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000784[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000784[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000784[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000784, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000788[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000788[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000788[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000788[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000788[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000788[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000788[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000788[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000788[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000788, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800078C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800078C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800078C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800078C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800078C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800078C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800078C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800078C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800078C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800078C, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000790[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF8000790[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000790[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000790[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000790[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000790[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000790[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000790[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000790[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000790, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000794[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000794[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000794[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000794[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000794[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000794[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000794[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000794[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000794[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000794, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000798[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000798[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000798[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000798[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000798[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000798[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000798[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000798[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000798[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000798, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800079C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800079C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800079C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800079C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800079C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800079C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800079C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800079C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800079C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800079C, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A0[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A0, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A4[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A4, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A8[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A8[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A8[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A8, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007AC[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007AC[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007AC[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007AC[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007AC[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007AC[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007AC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007AC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007AC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007AC, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007B0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007B0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007B0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007B0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007B0[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007B0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B0, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007B4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007B4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007B4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007B4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007B4[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007B4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B4, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007B8[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007B8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B8, 0x00003F01U ,0x00000200U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007BC[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. Speed = 0 + // .. ==> 0XF80007BC[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007BC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007BC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007BC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007BC, 0x00003F01U ,0x00000201U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007C0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007C0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 7 + // .. ==> 0XF80007C0[7:5] = 0x00000007U + // .. ==> MASK : 0x000000E0U VAL : 0x000000E0U + // .. Speed = 0 + // .. ==> 0XF80007C0[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C0, 0x00003FFFU ,0x000002E0U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007C4[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007C4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 7 + // .. ==> 0XF80007C4[7:5] = 0x00000007U + // .. ==> MASK : 0x000000E0U VAL : 0x000000E0U + // .. Speed = 0 + // .. ==> 0XF80007C4[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C4, 0x00003FFFU ,0x000002E1U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007C8[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007C8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C8[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF80007C8[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007C8[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C8, 0x00003FFFU ,0x00000201U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007CC[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007CC[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007CC[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007CC[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF80007CC[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007CC[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007CC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007CC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007CC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007CC, 0x00003FFFU ,0x00000201U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007D0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007D0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007D0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007D0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007D0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 0 + // .. ==> 0XF80007D0[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007D0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007D0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007D0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007D0, 0x00003FFFU ,0x00000280U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007D4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007D4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007D4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007D4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007D4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 0 + // .. ==> 0XF80007D4[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007D4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007D4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007D4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007D4, 0x00003FFFU ,0x00000280U), + // .. SDIO0_CD_SEL = 47 + // .. ==> 0XF8000830[21:16] = 0x0000002FU + // .. ==> MASK : 0x003F0000U VAL : 0x002F0000U + // .. + EMIT_MASKWRITE(0XF8000830, 0x003F0000U ,0x002F0000U), + // .. FINISH: MIO PROGRAMMING + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_peripherals_init_data_1_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: DDR TERM/IBUF_DISABLE_MODE SETTINGS + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B48[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B48[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B48, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B4C[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B4C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B4C, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B50[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B50[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B50, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B54[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B54[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B54, 0x00000180U ,0x00000180U), + // .. FINISH: DDR TERM/IBUF_DISABLE_MODE SETTINGS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // .. START: SRAM/NOR SET OPMODE + // .. FINISH: SRAM/NOR SET OPMODE + // .. START: UART REGISTERS + // .. BDIV = 0x5 + // .. ==> 0XE0001034[7:0] = 0x00000005U + // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. + EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000005U), + // .. CD = 0x9 + // .. ==> 0XE0001018[15:0] = 0x00000009U + // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + // .. + EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x00000009U), + // .. STPBRK = 0x0 + // .. ==> 0XE0001000[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. STTBRK = 0x0 + // .. ==> 0XE0001000[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. RSTTO = 0x0 + // .. ==> 0XE0001000[6:6] = 0x00000000U + // .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. TXDIS = 0x0 + // .. ==> 0XE0001000[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. TXEN = 0x1 + // .. ==> 0XE0001000[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. RXDIS = 0x0 + // .. ==> 0XE0001000[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. RXEN = 0x1 + // .. ==> 0XE0001000[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. TXRES = 0x1 + // .. ==> 0XE0001000[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. RXRES = 0x1 + // .. ==> 0XE0001000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XE0001000, 0x000001FFU ,0x00000017U), + // .. IRMODE = 0x0 + // .. ==> 0XE0001004[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. UCLKEN = 0x0 + // .. ==> 0XE0001004[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. CHMODE = 0x0 + // .. ==> 0XE0001004[9:8] = 0x00000000U + // .. ==> MASK : 0x00000300U VAL : 0x00000000U + // .. NBSTOP = 0x0 + // .. ==> 0XE0001004[7:6] = 0x00000000U + // .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. PAR = 0x4 + // .. ==> 0XE0001004[5:3] = 0x00000004U + // .. ==> MASK : 0x00000038U VAL : 0x00000020U + // .. CHRL = 0x0 + // .. ==> 0XE0001004[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. CLKS = 0x0 + // .. ==> 0XE0001004[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XE0001004, 0x00000FFFU ,0x00000020U), + // .. BDIV = 0x5 + // .. ==> 0XE0000034[7:0] = 0x00000005U + // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. + EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000005U), + // .. CD = 0x9 + // .. ==> 0XE0000018[15:0] = 0x00000009U + // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + // .. + EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x00000009U), + // .. STPBRK = 0x0 + // .. ==> 0XE0000000[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. STTBRK = 0x0 + // .. ==> 0XE0000000[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. RSTTO = 0x0 + // .. ==> 0XE0000000[6:6] = 0x00000000U + // .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. TXDIS = 0x0 + // .. ==> 0XE0000000[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. TXEN = 0x1 + // .. ==> 0XE0000000[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. RXDIS = 0x0 + // .. ==> 0XE0000000[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. RXEN = 0x1 + // .. ==> 0XE0000000[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. TXRES = 0x1 + // .. ==> 0XE0000000[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. RXRES = 0x1 + // .. ==> 0XE0000000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XE0000000, 0x000001FFU ,0x00000017U), + // .. IRMODE = 0x0 + // .. ==> 0XE0000004[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. UCLKEN = 0x0 + // .. ==> 0XE0000004[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. CHMODE = 0x0 + // .. ==> 0XE0000004[9:8] = 0x00000000U + // .. ==> MASK : 0x00000300U VAL : 0x00000000U + // .. NBSTOP = 0x0 + // .. ==> 0XE0000004[7:6] = 0x00000000U + // .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. PAR = 0x4 + // .. ==> 0XE0000004[5:3] = 0x00000004U + // .. ==> MASK : 0x00000038U VAL : 0x00000020U + // .. CHRL = 0x0 + // .. ==> 0XE0000004[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. CLKS = 0x0 + // .. ==> 0XE0000004[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XE0000004, 0x00000FFFU ,0x00000020U), + // .. FINISH: UART REGISTERS + // .. START: PL POWER ON RESET REGISTERS + // .. PCFG_POR_CNT_4K = 0 + // .. ==> 0XF8007000[29:29] = 0x00000000U + // .. ==> MASK : 0x20000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8007000, 0x20000000U ,0x00000000U), + // .. FINISH: PL POWER ON RESET REGISTERS + // .. START: SMC TIMING CALCULATION REGISTER UPDATE + // .. .. START: NAND SET CYCLE + // .. .. FINISH: NAND SET CYCLE + // .. .. START: OPMODE + // .. .. FINISH: OPMODE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: SRAM/NOR CS0 SET CYCLE + // .. .. FINISH: SRAM/NOR CS0 SET CYCLE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: NOR CS0 BASE ADDRESS + // .. .. FINISH: NOR CS0 BASE ADDRESS + // .. .. START: SRAM/NOR CS1 SET CYCLE + // .. .. FINISH: SRAM/NOR CS1 SET CYCLE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: NOR CS1 BASE ADDRESS + // .. .. FINISH: NOR CS1 BASE ADDRESS + // .. .. START: USB RESET + // .. .. .. START: DIR MODE BANK 0 + // .. .. .. FINISH: DIR MODE BANK 0 + // .. .. .. START: DIR MODE BANK 1 + // .. .. .. DIRECTION_1 = 0x4000 + // .. .. .. ==> 0XE000A244[21:0] = 0x00004000U + // .. .. .. ==> MASK : 0x003FFFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A244, 0x003FFFFFU ,0x00004000U), + // .. .. .. FINISH: DIR MODE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x4000 + // .. .. .. ==> 0XE000A008[15:0] = 0x00004000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF4000U), + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE BANK 0 + // .. .. .. FINISH: OUTPUT ENABLE BANK 0 + // .. .. .. START: OUTPUT ENABLE BANK 1 + // .. .. .. OP_ENABLE_1 = 0x4000 + // .. .. .. ==> 0XE000A248[21:0] = 0x00004000U + // .. .. .. ==> MASK : 0x003FFFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A248, 0x003FFFFFU ,0x00004000U), + // .. .. .. FINISH: OUTPUT ENABLE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x0 + // .. .. .. ==> 0XE000A008[15:0] = 0x00000000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF0000U), + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x4000 + // .. .. .. ==> 0XE000A008[15:0] = 0x00004000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF4000U), + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: USB RESET + // .. .. START: ENET RESET + // .. .. .. START: DIR MODE BANK 0 + // .. .. .. FINISH: DIR MODE BANK 0 + // .. .. .. START: DIR MODE BANK 1 + // .. .. .. FINISH: DIR MODE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE BANK 0 + // .. .. .. FINISH: OUTPUT ENABLE BANK 0 + // .. .. .. START: OUTPUT ENABLE BANK 1 + // .. .. .. FINISH: OUTPUT ENABLE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: ENET RESET + // .. .. START: I2C RESET + // .. .. .. START: DIR MODE GPIO BANK0 + // .. .. .. FINISH: DIR MODE GPIO BANK0 + // .. .. .. START: DIR MODE GPIO BANK1 + // .. .. .. FINISH: DIR MODE GPIO BANK1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE + // .. .. .. FINISH: OUTPUT ENABLE + // .. .. .. START: OUTPUT ENABLE + // .. .. .. FINISH: OUTPUT ENABLE + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: I2C RESET + // .. FINISH: SMC TIMING CALCULATION REGISTER UPDATE + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_post_config_1_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: ENABLING LEVEL SHIFTER + // .. USER_INP_ICT_EN_0 = 3 + // .. ==> 0XF8000900[1:0] = 0x00000003U + // .. ==> MASK : 0x00000003U VAL : 0x00000003U + // .. USER_INP_ICT_EN_1 = 3 + // .. ==> 0XF8000900[3:2] = 0x00000003U + // .. ==> MASK : 0x0000000CU VAL : 0x0000000CU + // .. + EMIT_MASKWRITE(0XF8000900, 0x0000000FU ,0x0000000FU), + // .. FINISH: ENABLING LEVEL SHIFTER + // .. START: FPGA RESETS TO 1 + // .. reserved_3 = 127 + // .. ==> 0XF8000240[31:25] = 0x0000007FU + // .. ==> MASK : 0xFE000000U VAL : 0xFE000000U + // .. FPGA_ACP_RST = 1 + // .. ==> 0XF8000240[24:24] = 0x00000001U + // .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. FPGA_AXDS3_RST = 1 + // .. ==> 0XF8000240[23:23] = 0x00000001U + // .. ==> MASK : 0x00800000U VAL : 0x00800000U + // .. FPGA_AXDS2_RST = 1 + // .. ==> 0XF8000240[22:22] = 0x00000001U + // .. ==> MASK : 0x00400000U VAL : 0x00400000U + // .. FPGA_AXDS1_RST = 1 + // .. ==> 0XF8000240[21:21] = 0x00000001U + // .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. FPGA_AXDS0_RST = 1 + // .. ==> 0XF8000240[20:20] = 0x00000001U + // .. ==> MASK : 0x00100000U VAL : 0x00100000U + // .. reserved_2 = 3 + // .. ==> 0XF8000240[19:18] = 0x00000003U + // .. ==> MASK : 0x000C0000U VAL : 0x000C0000U + // .. FSSW1_FPGA_RST = 1 + // .. ==> 0XF8000240[17:17] = 0x00000001U + // .. ==> MASK : 0x00020000U VAL : 0x00020000U + // .. FSSW0_FPGA_RST = 1 + // .. ==> 0XF8000240[16:16] = 0x00000001U + // .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. reserved_1 = 15 + // .. ==> 0XF8000240[15:14] = 0x0000000FU + // .. ==> MASK : 0x0000C000U VAL : 0x0000C000U + // .. FPGA_FMSW1_RST = 1 + // .. ==> 0XF8000240[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. FPGA_FMSW0_RST = 1 + // .. ==> 0XF8000240[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. FPGA_DMA3_RST = 1 + // .. ==> 0XF8000240[11:11] = 0x00000001U + // .. ==> MASK : 0x00000800U VAL : 0x00000800U + // .. FPGA_DMA2_RST = 1 + // .. ==> 0XF8000240[10:10] = 0x00000001U + // .. ==> MASK : 0x00000400U VAL : 0x00000400U + // .. FPGA_DMA1_RST = 1 + // .. ==> 0XF8000240[9:9] = 0x00000001U + // .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. FPGA_DMA0_RST = 1 + // .. ==> 0XF8000240[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. reserved = 15 + // .. ==> 0XF8000240[7:4] = 0x0000000FU + // .. ==> MASK : 0x000000F0U VAL : 0x000000F0U + // .. FPGA3_OUT_RST = 1 + // .. ==> 0XF8000240[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. FPGA2_OUT_RST = 1 + // .. ==> 0XF8000240[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. FPGA1_OUT_RST = 1 + // .. ==> 0XF8000240[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. FPGA0_OUT_RST = 1 + // .. ==> 0XF8000240[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XF8000240, 0xFFFFFFFFU ,0xFFFFFFFFU), + // .. FINISH: FPGA RESETS TO 1 + // .. START: FPGA RESETS TO 0 + // .. reserved_3 = 0 + // .. ==> 0XF8000240[31:25] = 0x00000000U + // .. ==> MASK : 0xFE000000U VAL : 0x00000000U + // .. FPGA_ACP_RST = 0 + // .. ==> 0XF8000240[24:24] = 0x00000000U + // .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. FPGA_AXDS3_RST = 0 + // .. ==> 0XF8000240[23:23] = 0x00000000U + // .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. FPGA_AXDS2_RST = 0 + // .. ==> 0XF8000240[22:22] = 0x00000000U + // .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. FPGA_AXDS1_RST = 0 + // .. ==> 0XF8000240[21:21] = 0x00000000U + // .. ==> MASK : 0x00200000U VAL : 0x00000000U + // .. FPGA_AXDS0_RST = 0 + // .. ==> 0XF8000240[20:20] = 0x00000000U + // .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. reserved_2 = 0 + // .. ==> 0XF8000240[19:18] = 0x00000000U + // .. ==> MASK : 0x000C0000U VAL : 0x00000000U + // .. FSSW1_FPGA_RST = 0 + // .. ==> 0XF8000240[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. FSSW0_FPGA_RST = 0 + // .. ==> 0XF8000240[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reserved_1 = 0 + // .. ==> 0XF8000240[15:14] = 0x00000000U + // .. ==> MASK : 0x0000C000U VAL : 0x00000000U + // .. FPGA_FMSW1_RST = 0 + // .. ==> 0XF8000240[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. FPGA_FMSW0_RST = 0 + // .. ==> 0XF8000240[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. FPGA_DMA3_RST = 0 + // .. ==> 0XF8000240[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. FPGA_DMA2_RST = 0 + // .. ==> 0XF8000240[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. FPGA_DMA1_RST = 0 + // .. ==> 0XF8000240[9:9] = 0x00000000U + // .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. FPGA_DMA0_RST = 0 + // .. ==> 0XF8000240[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. reserved = 0 + // .. ==> 0XF8000240[7:4] = 0x00000000U + // .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. FPGA3_OUT_RST = 0 + // .. ==> 0XF8000240[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. FPGA2_OUT_RST = 0 + // .. ==> 0XF8000240[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. FPGA1_OUT_RST = 0 + // .. ==> 0XF8000240[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. FPGA0_OUT_RST = 0 + // .. ==> 0XF8000240[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000240, 0xFFFFFFFFU ,0x00000000U), + // .. FINISH: FPGA RESETS TO 0 + // .. START: AFI REGISTERS + // .. .. START: AFI0 REGISTERS + // .. .. FINISH: AFI0 REGISTERS + // .. .. START: AFI1 REGISTERS + // .. .. FINISH: AFI1 REGISTERS + // .. .. START: AFI2 REGISTERS + // .. .. FINISH: AFI2 REGISTERS + // .. .. START: AFI3 REGISTERS + // .. .. FINISH: AFI3 REGISTERS + // .. FINISH: AFI REGISTERS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_pll_init_data_2_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: PLL SLCR REGISTERS + // .. .. START: ARM PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000110[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000110[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x177 + // .. .. ==> 0XF8000110[21:12] = 0x00000177U + // .. .. ==> MASK : 0x003FF000U VAL : 0x00177000U + // .. .. + EMIT_MASKWRITE(0XF8000110, 0x003FFFF0U ,0x001772C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x1a + // .. .. .. ==> 0XF8000100[18:12] = 0x0000001AU + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x0001A000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x0007F000U ,0x0001A000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000100[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000100[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000100[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. ARM_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000001U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000100[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. .. SRCSEL = 0x0 + // .. .. .. ==> 0XF8000120[5:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. .. .. DIVISOR = 0x2 + // .. .. .. ==> 0XF8000120[13:8] = 0x00000002U + // .. .. .. ==> MASK : 0x00003F00U VAL : 0x00000200U + // .. .. .. CPU_6OR4XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[24:24] = 0x00000001U + // .. .. .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. .. .. CPU_3OR2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[25:25] = 0x00000001U + // .. .. .. ==> MASK : 0x02000000U VAL : 0x02000000U + // .. .. .. CPU_2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[26:26] = 0x00000001U + // .. .. .. ==> MASK : 0x04000000U VAL : 0x04000000U + // .. .. .. CPU_1XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[27:27] = 0x00000001U + // .. .. .. ==> MASK : 0x08000000U VAL : 0x08000000U + // .. .. .. CPU_PERI_CLKACT = 0x1 + // .. .. .. ==> 0XF8000120[28:28] = 0x00000001U + // .. .. .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000120, 0x1F003F30U ,0x1F000200U), + // .. .. FINISH: ARM PLL INIT + // .. .. START: DDR PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000114[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000114[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x1db + // .. .. ==> 0XF8000114[21:12] = 0x000001DBU + // .. .. ==> MASK : 0x003FF000U VAL : 0x001DB000U + // .. .. + EMIT_MASKWRITE(0XF8000114, 0x003FFFF0U ,0x001DB2C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x15 + // .. .. .. ==> 0XF8000104[18:12] = 0x00000015U + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x00015000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x0007F000U ,0x00015000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000104[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000104[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000104[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. DDR_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[1:1] = 0x00000001U + // .. .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000002U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000104[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. .. DDR_3XCLKACT = 0x1 + // .. .. .. ==> 0XF8000124[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. DDR_2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000124[1:1] = 0x00000001U + // .. .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. .. DDR_3XCLK_DIVISOR = 0x2 + // .. .. .. ==> 0XF8000124[25:20] = 0x00000002U + // .. .. .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. .. .. DDR_2XCLK_DIVISOR = 0x3 + // .. .. .. ==> 0XF8000124[31:26] = 0x00000003U + // .. .. .. ==> MASK : 0xFC000000U VAL : 0x0C000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000124, 0xFFF00003U ,0x0C200003U), + // .. .. FINISH: DDR PLL INIT + // .. .. START: IO PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000118[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000118[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x1f4 + // .. .. ==> 0XF8000118[21:12] = 0x000001F4U + // .. .. ==> MASK : 0x003FF000U VAL : 0x001F4000U + // .. .. + EMIT_MASKWRITE(0XF8000118, 0x003FFFF0U ,0x001F42C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x14 + // .. .. .. ==> 0XF8000108[18:12] = 0x00000014U + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x00014000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x0007F000U ,0x00014000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000108[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000108[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000108[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. IO_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[2:2] = 0x00000001U + // .. .. .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000004U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000108[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. FINISH: IO PLL INIT + // .. FINISH: PLL SLCR REGISTERS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_clock_init_data_2_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: CLOCK CONTROL SLCR REGISTERS + // .. CLKACT = 0x1 + // .. ==> 0XF8000128[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. DIVISOR0 = 0x34 + // .. ==> 0XF8000128[13:8] = 0x00000034U + // .. ==> MASK : 0x00003F00U VAL : 0x00003400U + // .. DIVISOR1 = 0x2 + // .. ==> 0XF8000128[25:20] = 0x00000002U + // .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. + EMIT_MASKWRITE(0XF8000128, 0x03F03F01U ,0x00203401U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000138[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000138[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000138, 0x00000011U ,0x00000001U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000140[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000140[6:4] = 0x00000000U + // .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. DIVISOR = 0x8 + // .. ==> 0XF8000140[13:8] = 0x00000008U + // .. ==> MASK : 0x00003F00U VAL : 0x00000800U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000140[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000140, 0x03F03F71U ,0x00100801U), + // .. CLKACT = 0x1 + // .. ==> 0XF800014C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF800014C[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x5 + // .. ==> 0XF800014C[13:8] = 0x00000005U + // .. ==> MASK : 0x00003F00U VAL : 0x00000500U + // .. + EMIT_MASKWRITE(0XF800014C, 0x00003F31U ,0x00000501U), + // .. CLKACT0 = 0x1 + // .. ==> 0XF8000150[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. CLKACT1 = 0x0 + // .. ==> 0XF8000150[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000150[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x14 + // .. ==> 0XF8000150[13:8] = 0x00000014U + // .. ==> MASK : 0x00003F00U VAL : 0x00001400U + // .. + EMIT_MASKWRITE(0XF8000150, 0x00003F33U ,0x00001401U), + // .. CLKACT0 = 0x1 + // .. ==> 0XF8000154[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. CLKACT1 = 0x1 + // .. ==> 0XF8000154[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000154[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x14 + // .. ==> 0XF8000154[13:8] = 0x00000014U + // .. ==> MASK : 0x00003F00U VAL : 0x00001400U + // .. + EMIT_MASKWRITE(0XF8000154, 0x00003F33U ,0x00001403U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000168[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000168[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x5 + // .. ==> 0XF8000168[13:8] = 0x00000005U + // .. ==> MASK : 0x00003F00U VAL : 0x00000500U + // .. + EMIT_MASKWRITE(0XF8000168, 0x00003F31U ,0x00000501U), + // .. SRCSEL = 0x0 + // .. ==> 0XF8000170[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR0 = 0xa + // .. ==> 0XF8000170[13:8] = 0x0000000AU + // .. ==> MASK : 0x00003F00U VAL : 0x00000A00U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000170[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000170, 0x03F03F30U ,0x00100A00U), + // .. SRCSEL = 0x3 + // .. ==> 0XF8000180[5:4] = 0x00000003U + // .. ==> MASK : 0x00000030U VAL : 0x00000030U + // .. DIVISOR0 = 0x6 + // .. ==> 0XF8000180[13:8] = 0x00000006U + // .. ==> MASK : 0x00003F00U VAL : 0x00000600U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000180[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000180, 0x03F03F30U ,0x00100630U), + // .. SRCSEL = 0x2 + // .. ==> 0XF8000190[5:4] = 0x00000002U + // .. ==> MASK : 0x00000030U VAL : 0x00000020U + // .. DIVISOR0 = 0x35 + // .. ==> 0XF8000190[13:8] = 0x00000035U + // .. ==> MASK : 0x00003F00U VAL : 0x00003500U + // .. DIVISOR1 = 0x2 + // .. ==> 0XF8000190[25:20] = 0x00000002U + // .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. + EMIT_MASKWRITE(0XF8000190, 0x03F03F30U ,0x00203520U), + // .. SRCSEL = 0x0 + // .. ==> 0XF80001A0[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR0 = 0xa + // .. ==> 0XF80001A0[13:8] = 0x0000000AU + // .. ==> MASK : 0x00003F00U VAL : 0x00000A00U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF80001A0[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF80001A0, 0x03F03F30U ,0x00100A00U), + // .. CLK_621_TRUE = 0x1 + // .. ==> 0XF80001C4[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XF80001C4, 0x00000001U ,0x00000001U), + // .. DMA_CPU_2XCLKACT = 0x1 + // .. ==> 0XF800012C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. USB0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. USB1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. GEM0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[6:6] = 0x00000001U + // .. ==> MASK : 0x00000040U VAL : 0x00000040U + // .. GEM1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. SDI0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[10:10] = 0x00000001U + // .. ==> MASK : 0x00000400U VAL : 0x00000400U + // .. SDI1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. SPI0_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[14:14] = 0x00000000U + // .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. SPI1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[15:15] = 0x00000000U + // .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. CAN0_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. CAN1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. I2C0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[18:18] = 0x00000001U + // .. ==> MASK : 0x00040000U VAL : 0x00040000U + // .. I2C1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. UART0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[20:20] = 0x00000001U + // .. ==> MASK : 0x00100000U VAL : 0x00100000U + // .. UART1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[21:21] = 0x00000001U + // .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. GPIO_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[22:22] = 0x00000001U + // .. ==> MASK : 0x00400000U VAL : 0x00400000U + // .. LQSPI_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[23:23] = 0x00000001U + // .. ==> MASK : 0x00800000U VAL : 0x00800000U + // .. SMC_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[24:24] = 0x00000001U + // .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. + EMIT_MASKWRITE(0XF800012C, 0x01FFCCCDU ,0x01FC044DU), + // .. FINISH: CLOCK CONTROL SLCR REGISTERS + // .. START: THIS SHOULD BE BLANK + // .. FINISH: THIS SHOULD BE BLANK + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_ddr_init_data_2_0[] = { + // START: top + // .. START: DDR INITIALIZATION + // .. .. START: LOCK DDR + // .. .. reg_ddrc_soft_rstb = 0 + // .. .. ==> 0XF8006000[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_powerdown_en = 0x0 + // .. .. ==> 0XF8006000[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_ddrc_data_bus_width = 0x0 + // .. .. ==> 0XF8006000[3:2] = 0x00000000U + // .. .. ==> MASK : 0x0000000CU VAL : 0x00000000U + // .. .. reg_ddrc_burst8_refresh = 0x0 + // .. .. ==> 0XF8006000[6:4] = 0x00000000U + // .. .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. .. reg_ddrc_rdwr_idle_gap = 0x1 + // .. .. ==> 0XF8006000[13:7] = 0x00000001U + // .. .. ==> MASK : 0x00003F80U VAL : 0x00000080U + // .. .. reg_ddrc_dis_rd_bypass = 0x0 + // .. .. ==> 0XF8006000[14:14] = 0x00000000U + // .. .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_act_bypass = 0x0 + // .. .. ==> 0XF8006000[15:15] = 0x00000000U + // .. .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_auto_refresh = 0x0 + // .. .. ==> 0XF8006000[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006000, 0x0001FFFFU ,0x00000080U), + // .. .. FINISH: LOCK DDR + // .. .. reg_ddrc_t_rfc_nom_x32 = 0x7f + // .. .. ==> 0XF8006004[11:0] = 0x0000007FU + // .. .. ==> MASK : 0x00000FFFU VAL : 0x0000007FU + // .. .. reg_ddrc_active_ranks = 0x1 + // .. .. ==> 0XF8006004[13:12] = 0x00000001U + // .. .. ==> MASK : 0x00003000U VAL : 0x00001000U + // .. .. reg_ddrc_addrmap_cs_bit0 = 0x0 + // .. .. ==> 0XF8006004[18:14] = 0x00000000U + // .. .. ==> MASK : 0x0007C000U VAL : 0x00000000U + // .. .. reg_ddrc_wr_odt_block = 0x1 + // .. .. ==> 0XF8006004[20:19] = 0x00000001U + // .. .. ==> MASK : 0x00180000U VAL : 0x00080000U + // .. .. reg_ddrc_diff_rank_rd_2cycle_gap = 0x0 + // .. .. ==> 0XF8006004[21:21] = 0x00000000U + // .. .. ==> MASK : 0x00200000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_cs_bit1 = 0x0 + // .. .. ==> 0XF8006004[26:22] = 0x00000000U + // .. .. ==> MASK : 0x07C00000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_open_bank = 0x0 + // .. .. ==> 0XF8006004[27:27] = 0x00000000U + // .. .. ==> MASK : 0x08000000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_4bank_ram = 0x0 + // .. .. ==> 0XF8006004[28:28] = 0x00000000U + // .. .. ==> MASK : 0x10000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006004, 0x1FFFFFFFU ,0x0008107FU), + // .. .. reg_ddrc_hpr_min_non_critical_x32 = 0xf + // .. .. ==> 0XF8006008[10:0] = 0x0000000FU + // .. .. ==> MASK : 0x000007FFU VAL : 0x0000000FU + // .. .. reg_ddrc_hpr_max_starve_x32 = 0xf + // .. .. ==> 0XF8006008[21:11] = 0x0000000FU + // .. .. ==> MASK : 0x003FF800U VAL : 0x00007800U + // .. .. reg_ddrc_hpr_xact_run_length = 0xf + // .. .. ==> 0XF8006008[25:22] = 0x0000000FU + // .. .. ==> MASK : 0x03C00000U VAL : 0x03C00000U + // .. .. + EMIT_MASKWRITE(0XF8006008, 0x03FFFFFFU ,0x03C0780FU), + // .. .. reg_ddrc_lpr_min_non_critical_x32 = 0x1 + // .. .. ==> 0XF800600C[10:0] = 0x00000001U + // .. .. ==> MASK : 0x000007FFU VAL : 0x00000001U + // .. .. reg_ddrc_lpr_max_starve_x32 = 0x2 + // .. .. ==> 0XF800600C[21:11] = 0x00000002U + // .. .. ==> MASK : 0x003FF800U VAL : 0x00001000U + // .. .. reg_ddrc_lpr_xact_run_length = 0x8 + // .. .. ==> 0XF800600C[25:22] = 0x00000008U + // .. .. ==> MASK : 0x03C00000U VAL : 0x02000000U + // .. .. + EMIT_MASKWRITE(0XF800600C, 0x03FFFFFFU ,0x02001001U), + // .. .. reg_ddrc_w_min_non_critical_x32 = 0x1 + // .. .. ==> 0XF8006010[10:0] = 0x00000001U + // .. .. ==> MASK : 0x000007FFU VAL : 0x00000001U + // .. .. reg_ddrc_w_xact_run_length = 0x8 + // .. .. ==> 0XF8006010[14:11] = 0x00000008U + // .. .. ==> MASK : 0x00007800U VAL : 0x00004000U + // .. .. reg_ddrc_w_max_starve_x32 = 0x2 + // .. .. ==> 0XF8006010[25:15] = 0x00000002U + // .. .. ==> MASK : 0x03FF8000U VAL : 0x00010000U + // .. .. + EMIT_MASKWRITE(0XF8006010, 0x03FFFFFFU ,0x00014001U), + // .. .. reg_ddrc_t_rc = 0x1a + // .. .. ==> 0XF8006014[5:0] = 0x0000001AU + // .. .. ==> MASK : 0x0000003FU VAL : 0x0000001AU + // .. .. reg_ddrc_t_rfc_min = 0x54 + // .. .. ==> 0XF8006014[13:6] = 0x00000054U + // .. .. ==> MASK : 0x00003FC0U VAL : 0x00001500U + // .. .. reg_ddrc_post_selfref_gap_x32 = 0x10 + // .. .. ==> 0XF8006014[20:14] = 0x00000010U + // .. .. ==> MASK : 0x001FC000U VAL : 0x00040000U + // .. .. + EMIT_MASKWRITE(0XF8006014, 0x001FFFFFU ,0x0004151AU), + // .. .. reg_ddrc_wr2pre = 0x12 + // .. .. ==> 0XF8006018[4:0] = 0x00000012U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000012U + // .. .. reg_ddrc_powerdown_to_x32 = 0x6 + // .. .. ==> 0XF8006018[9:5] = 0x00000006U + // .. .. ==> MASK : 0x000003E0U VAL : 0x000000C0U + // .. .. reg_ddrc_t_faw = 0x15 + // .. .. ==> 0XF8006018[15:10] = 0x00000015U + // .. .. ==> MASK : 0x0000FC00U VAL : 0x00005400U + // .. .. reg_ddrc_t_ras_max = 0x23 + // .. .. ==> 0XF8006018[21:16] = 0x00000023U + // .. .. ==> MASK : 0x003F0000U VAL : 0x00230000U + // .. .. reg_ddrc_t_ras_min = 0x13 + // .. .. ==> 0XF8006018[26:22] = 0x00000013U + // .. .. ==> MASK : 0x07C00000U VAL : 0x04C00000U + // .. .. reg_ddrc_t_cke = 0x4 + // .. .. ==> 0XF8006018[31:28] = 0x00000004U + // .. .. ==> MASK : 0xF0000000U VAL : 0x40000000U + // .. .. + EMIT_MASKWRITE(0XF8006018, 0xF7FFFFFFU ,0x44E354D2U), + // .. .. reg_ddrc_write_latency = 0x5 + // .. .. ==> 0XF800601C[4:0] = 0x00000005U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000005U + // .. .. reg_ddrc_rd2wr = 0x7 + // .. .. ==> 0XF800601C[9:5] = 0x00000007U + // .. .. ==> MASK : 0x000003E0U VAL : 0x000000E0U + // .. .. reg_ddrc_wr2rd = 0xe + // .. .. ==> 0XF800601C[14:10] = 0x0000000EU + // .. .. ==> MASK : 0x00007C00U VAL : 0x00003800U + // .. .. reg_ddrc_t_xp = 0x4 + // .. .. ==> 0XF800601C[19:15] = 0x00000004U + // .. .. ==> MASK : 0x000F8000U VAL : 0x00020000U + // .. .. reg_ddrc_pad_pd = 0x0 + // .. .. ==> 0XF800601C[22:20] = 0x00000000U + // .. .. ==> MASK : 0x00700000U VAL : 0x00000000U + // .. .. reg_ddrc_rd2pre = 0x4 + // .. .. ==> 0XF800601C[27:23] = 0x00000004U + // .. .. ==> MASK : 0x0F800000U VAL : 0x02000000U + // .. .. reg_ddrc_t_rcd = 0x7 + // .. .. ==> 0XF800601C[31:28] = 0x00000007U + // .. .. ==> MASK : 0xF0000000U VAL : 0x70000000U + // .. .. + EMIT_MASKWRITE(0XF800601C, 0xFFFFFFFFU ,0x720238E5U), + // .. .. reg_ddrc_t_ccd = 0x4 + // .. .. ==> 0XF8006020[4:2] = 0x00000004U + // .. .. ==> MASK : 0x0000001CU VAL : 0x00000010U + // .. .. reg_ddrc_t_rrd = 0x6 + // .. .. ==> 0XF8006020[7:5] = 0x00000006U + // .. .. ==> MASK : 0x000000E0U VAL : 0x000000C0U + // .. .. reg_ddrc_refresh_margin = 0x2 + // .. .. ==> 0XF8006020[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. reg_ddrc_t_rp = 0x7 + // .. .. ==> 0XF8006020[15:12] = 0x00000007U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00007000U + // .. .. reg_ddrc_refresh_to_x32 = 0x8 + // .. .. ==> 0XF8006020[20:16] = 0x00000008U + // .. .. ==> MASK : 0x001F0000U VAL : 0x00080000U + // .. .. reg_ddrc_sdram = 0x1 + // .. .. ==> 0XF8006020[21:21] = 0x00000001U + // .. .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. .. reg_ddrc_mobile = 0x0 + // .. .. ==> 0XF8006020[22:22] = 0x00000000U + // .. .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. .. reg_ddrc_clock_stop_en = 0x0 + // .. .. ==> 0XF8006020[23:23] = 0x00000000U + // .. .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. .. reg_ddrc_read_latency = 0x7 + // .. .. ==> 0XF8006020[28:24] = 0x00000007U + // .. .. ==> MASK : 0x1F000000U VAL : 0x07000000U + // .. .. reg_phy_mode_ddr1_ddr2 = 0x1 + // .. .. ==> 0XF8006020[29:29] = 0x00000001U + // .. .. ==> MASK : 0x20000000U VAL : 0x20000000U + // .. .. reg_ddrc_dis_pad_pd = 0x0 + // .. .. ==> 0XF8006020[30:30] = 0x00000000U + // .. .. ==> MASK : 0x40000000U VAL : 0x00000000U + // .. .. reg_ddrc_loopback = 0x0 + // .. .. ==> 0XF8006020[31:31] = 0x00000000U + // .. .. ==> MASK : 0x80000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006020, 0xFFFFFFFCU ,0x272872D0U), + // .. .. reg_ddrc_en_2t_timing_mode = 0x0 + // .. .. ==> 0XF8006024[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_prefer_write = 0x0 + // .. .. ==> 0XF8006024[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_ddrc_max_rank_rd = 0xf + // .. .. ==> 0XF8006024[5:2] = 0x0000000FU + // .. .. ==> MASK : 0x0000003CU VAL : 0x0000003CU + // .. .. reg_ddrc_mr_wr = 0x0 + // .. .. ==> 0XF8006024[6:6] = 0x00000000U + // .. .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. .. reg_ddrc_mr_addr = 0x0 + // .. .. ==> 0XF8006024[8:7] = 0x00000000U + // .. .. ==> MASK : 0x00000180U VAL : 0x00000000U + // .. .. reg_ddrc_mr_data = 0x0 + // .. .. ==> 0XF8006024[24:9] = 0x00000000U + // .. .. ==> MASK : 0x01FFFE00U VAL : 0x00000000U + // .. .. ddrc_reg_mr_wr_busy = 0x0 + // .. .. ==> 0XF8006024[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. reg_ddrc_mr_type = 0x0 + // .. .. ==> 0XF8006024[26:26] = 0x00000000U + // .. .. ==> MASK : 0x04000000U VAL : 0x00000000U + // .. .. reg_ddrc_mr_rdata_valid = 0x0 + // .. .. ==> 0XF8006024[27:27] = 0x00000000U + // .. .. ==> MASK : 0x08000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006024, 0x0FFFFFFFU ,0x0000003CU), + // .. .. reg_ddrc_final_wait_x32 = 0x7 + // .. .. ==> 0XF8006028[6:0] = 0x00000007U + // .. .. ==> MASK : 0x0000007FU VAL : 0x00000007U + // .. .. reg_ddrc_pre_ocd_x32 = 0x0 + // .. .. ==> 0XF8006028[10:7] = 0x00000000U + // .. .. ==> MASK : 0x00000780U VAL : 0x00000000U + // .. .. reg_ddrc_t_mrd = 0x4 + // .. .. ==> 0XF8006028[13:11] = 0x00000004U + // .. .. ==> MASK : 0x00003800U VAL : 0x00002000U + // .. .. + EMIT_MASKWRITE(0XF8006028, 0x00003FFFU ,0x00002007U), + // .. .. reg_ddrc_emr2 = 0x8 + // .. .. ==> 0XF800602C[15:0] = 0x00000008U + // .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000008U + // .. .. reg_ddrc_emr3 = 0x0 + // .. .. ==> 0XF800602C[31:16] = 0x00000000U + // .. .. ==> MASK : 0xFFFF0000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800602C, 0xFFFFFFFFU ,0x00000008U), + // .. .. reg_ddrc_mr = 0x930 + // .. .. ==> 0XF8006030[15:0] = 0x00000930U + // .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000930U + // .. .. reg_ddrc_emr = 0x4 + // .. .. ==> 0XF8006030[31:16] = 0x00000004U + // .. .. ==> MASK : 0xFFFF0000U VAL : 0x00040000U + // .. .. + EMIT_MASKWRITE(0XF8006030, 0xFFFFFFFFU ,0x00040930U), + // .. .. reg_ddrc_burst_rdwr = 0x4 + // .. .. ==> 0XF8006034[3:0] = 0x00000004U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000004U + // .. .. reg_ddrc_pre_cke_x1024 = 0x101 + // .. .. ==> 0XF8006034[13:4] = 0x00000101U + // .. .. ==> MASK : 0x00003FF0U VAL : 0x00001010U + // .. .. reg_ddrc_post_cke_x1024 = 0x1 + // .. .. ==> 0XF8006034[25:16] = 0x00000001U + // .. .. ==> MASK : 0x03FF0000U VAL : 0x00010000U + // .. .. reg_ddrc_burstchop = 0x0 + // .. .. ==> 0XF8006034[28:28] = 0x00000000U + // .. .. ==> MASK : 0x10000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006034, 0x13FF3FFFU ,0x00011014U), + // .. .. reg_ddrc_force_low_pri_n = 0x0 + // .. .. ==> 0XF8006038[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_dis_dq = 0x0 + // .. .. ==> 0XF8006038[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_phy_debug_mode = 0x0 + // .. .. ==> 0XF8006038[6:6] = 0x00000000U + // .. .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. .. reg_phy_wr_level_start = 0x0 + // .. .. ==> 0XF8006038[7:7] = 0x00000000U + // .. .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. .. reg_phy_rd_level_start = 0x0 + // .. .. ==> 0XF8006038[8:8] = 0x00000000U + // .. .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. .. reg_phy_dq0_wait_t = 0x0 + // .. .. ==> 0XF8006038[12:9] = 0x00000000U + // .. .. ==> MASK : 0x00001E00U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006038, 0x00001FC3U ,0x00000000U), + // .. .. reg_ddrc_addrmap_bank_b0 = 0x7 + // .. .. ==> 0XF800603C[3:0] = 0x00000007U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000007U + // .. .. reg_ddrc_addrmap_bank_b1 = 0x7 + // .. .. ==> 0XF800603C[7:4] = 0x00000007U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000070U + // .. .. reg_ddrc_addrmap_bank_b2 = 0x7 + // .. .. ==> 0XF800603C[11:8] = 0x00000007U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000700U + // .. .. reg_ddrc_addrmap_col_b5 = 0x0 + // .. .. ==> 0XF800603C[15:12] = 0x00000000U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b6 = 0x0 + // .. .. ==> 0XF800603C[19:16] = 0x00000000U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800603C, 0x000FFFFFU ,0x00000777U), + // .. .. reg_ddrc_addrmap_col_b2 = 0x0 + // .. .. ==> 0XF8006040[3:0] = 0x00000000U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b3 = 0x0 + // .. .. ==> 0XF8006040[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b4 = 0x0 + // .. .. ==> 0XF8006040[11:8] = 0x00000000U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b7 = 0x0 + // .. .. ==> 0XF8006040[15:12] = 0x00000000U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b8 = 0x0 + // .. .. ==> 0XF8006040[19:16] = 0x00000000U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b9 = 0xf + // .. .. ==> 0XF8006040[23:20] = 0x0000000FU + // .. .. ==> MASK : 0x00F00000U VAL : 0x00F00000U + // .. .. reg_ddrc_addrmap_col_b10 = 0xf + // .. .. ==> 0XF8006040[27:24] = 0x0000000FU + // .. .. ==> MASK : 0x0F000000U VAL : 0x0F000000U + // .. .. reg_ddrc_addrmap_col_b11 = 0xf + // .. .. ==> 0XF8006040[31:28] = 0x0000000FU + // .. .. ==> MASK : 0xF0000000U VAL : 0xF0000000U + // .. .. + EMIT_MASKWRITE(0XF8006040, 0xFFFFFFFFU ,0xFFF00000U), + // .. .. reg_ddrc_addrmap_row_b0 = 0x6 + // .. .. ==> 0XF8006044[3:0] = 0x00000006U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000006U + // .. .. reg_ddrc_addrmap_row_b1 = 0x6 + // .. .. ==> 0XF8006044[7:4] = 0x00000006U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000060U + // .. .. reg_ddrc_addrmap_row_b2_11 = 0x6 + // .. .. ==> 0XF8006044[11:8] = 0x00000006U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000600U + // .. .. reg_ddrc_addrmap_row_b12 = 0x6 + // .. .. ==> 0XF8006044[15:12] = 0x00000006U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00006000U + // .. .. reg_ddrc_addrmap_row_b13 = 0x6 + // .. .. ==> 0XF8006044[19:16] = 0x00000006U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00060000U + // .. .. reg_ddrc_addrmap_row_b14 = 0xf + // .. .. ==> 0XF8006044[23:20] = 0x0000000FU + // .. .. ==> MASK : 0x00F00000U VAL : 0x00F00000U + // .. .. reg_ddrc_addrmap_row_b15 = 0xf + // .. .. ==> 0XF8006044[27:24] = 0x0000000FU + // .. .. ==> MASK : 0x0F000000U VAL : 0x0F000000U + // .. .. + EMIT_MASKWRITE(0XF8006044, 0x0FFFFFFFU ,0x0FF66666U), + // .. .. reg_ddrc_rank0_rd_odt = 0x0 + // .. .. ==> 0XF8006048[2:0] = 0x00000000U + // .. .. ==> MASK : 0x00000007U VAL : 0x00000000U + // .. .. reg_ddrc_rank0_wr_odt = 0x1 + // .. .. ==> 0XF8006048[5:3] = 0x00000001U + // .. .. ==> MASK : 0x00000038U VAL : 0x00000008U + // .. .. reg_ddrc_rank1_rd_odt = 0x1 + // .. .. ==> 0XF8006048[8:6] = 0x00000001U + // .. .. ==> MASK : 0x000001C0U VAL : 0x00000040U + // .. .. reg_ddrc_rank1_wr_odt = 0x1 + // .. .. ==> 0XF8006048[11:9] = 0x00000001U + // .. .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. .. reg_phy_rd_local_odt = 0x0 + // .. .. ==> 0XF8006048[13:12] = 0x00000000U + // .. .. ==> MASK : 0x00003000U VAL : 0x00000000U + // .. .. reg_phy_wr_local_odt = 0x3 + // .. .. ==> 0XF8006048[15:14] = 0x00000003U + // .. .. ==> MASK : 0x0000C000U VAL : 0x0000C000U + // .. .. reg_phy_idle_local_odt = 0x3 + // .. .. ==> 0XF8006048[17:16] = 0x00000003U + // .. .. ==> MASK : 0x00030000U VAL : 0x00030000U + // .. .. reg_ddrc_rank2_rd_odt = 0x0 + // .. .. ==> 0XF8006048[20:18] = 0x00000000U + // .. .. ==> MASK : 0x001C0000U VAL : 0x00000000U + // .. .. reg_ddrc_rank2_wr_odt = 0x0 + // .. .. ==> 0XF8006048[23:21] = 0x00000000U + // .. .. ==> MASK : 0x00E00000U VAL : 0x00000000U + // .. .. reg_ddrc_rank3_rd_odt = 0x0 + // .. .. ==> 0XF8006048[26:24] = 0x00000000U + // .. .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. .. reg_ddrc_rank3_wr_odt = 0x0 + // .. .. ==> 0XF8006048[29:27] = 0x00000000U + // .. .. ==> MASK : 0x38000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006048, 0x3FFFFFFFU ,0x0003C248U), + // .. .. reg_phy_rd_cmd_to_data = 0x0 + // .. .. ==> 0XF8006050[3:0] = 0x00000000U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. .. reg_phy_wr_cmd_to_data = 0x0 + // .. .. ==> 0XF8006050[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_phy_rdc_we_to_re_delay = 0x8 + // .. .. ==> 0XF8006050[11:8] = 0x00000008U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000800U + // .. .. reg_phy_rdc_fifo_rst_disable = 0x0 + // .. .. ==> 0XF8006050[15:15] = 0x00000000U + // .. .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. .. reg_phy_use_fixed_re = 0x1 + // .. .. ==> 0XF8006050[16:16] = 0x00000001U + // .. .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. .. reg_phy_rdc_fifo_rst_err_cnt_clr = 0x0 + // .. .. ==> 0XF8006050[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_phy_dis_phy_ctrl_rstn = 0x0 + // .. .. ==> 0XF8006050[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. reg_phy_clk_stall_level = 0x0 + // .. .. ==> 0XF8006050[19:19] = 0x00000000U + // .. .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. .. reg_phy_gatelvl_num_of_dq0 = 0x7 + // .. .. ==> 0XF8006050[27:24] = 0x00000007U + // .. .. ==> MASK : 0x0F000000U VAL : 0x07000000U + // .. .. reg_phy_wrlvl_num_of_dq0 = 0x7 + // .. .. ==> 0XF8006050[31:28] = 0x00000007U + // .. .. ==> MASK : 0xF0000000U VAL : 0x70000000U + // .. .. + EMIT_MASKWRITE(0XF8006050, 0xFF0F8FFFU ,0x77010800U), + // .. .. reg_ddrc_dll_calib_to_min_x1024 = 0x1 + // .. .. ==> 0XF8006058[7:0] = 0x00000001U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000001U + // .. .. reg_ddrc_dll_calib_to_max_x1024 = 0x1 + // .. .. ==> 0XF8006058[15:8] = 0x00000001U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00000100U + // .. .. reg_ddrc_dis_dll_calib = 0x0 + // .. .. ==> 0XF8006058[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006058, 0x0001FFFFU ,0x00000101U), + // .. .. reg_ddrc_rd_odt_delay = 0x3 + // .. .. ==> 0XF800605C[3:0] = 0x00000003U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000003U + // .. .. reg_ddrc_wr_odt_delay = 0x0 + // .. .. ==> 0XF800605C[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_ddrc_rd_odt_hold = 0x0 + // .. .. ==> 0XF800605C[11:8] = 0x00000000U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000000U + // .. .. reg_ddrc_wr_odt_hold = 0x5 + // .. .. ==> 0XF800605C[15:12] = 0x00000005U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00005000U + // .. .. + EMIT_MASKWRITE(0XF800605C, 0x0000FFFFU ,0x00005003U), + // .. .. reg_ddrc_pageclose = 0x0 + // .. .. ==> 0XF8006060[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_lpr_num_entries = 0x1f + // .. .. ==> 0XF8006060[6:1] = 0x0000001FU + // .. .. ==> MASK : 0x0000007EU VAL : 0x0000003EU + // .. .. reg_ddrc_auto_pre_en = 0x0 + // .. .. ==> 0XF8006060[7:7] = 0x00000000U + // .. .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. .. reg_ddrc_refresh_update_level = 0x0 + // .. .. ==> 0XF8006060[8:8] = 0x00000000U + // .. .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. .. reg_ddrc_dis_wc = 0x0 + // .. .. ==> 0XF8006060[9:9] = 0x00000000U + // .. .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. .. reg_ddrc_dis_collision_page_opt = 0x0 + // .. .. ==> 0XF8006060[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_ddrc_selfref_en = 0x0 + // .. .. ==> 0XF8006060[12:12] = 0x00000000U + // .. .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006060, 0x000017FFU ,0x0000003EU), + // .. .. reg_ddrc_go2critical_hysteresis = 0x0 + // .. .. ==> 0XF8006064[12:5] = 0x00000000U + // .. .. ==> MASK : 0x00001FE0U VAL : 0x00000000U + // .. .. reg_arb_go2critical_en = 0x1 + // .. .. ==> 0XF8006064[17:17] = 0x00000001U + // .. .. ==> MASK : 0x00020000U VAL : 0x00020000U + // .. .. + EMIT_MASKWRITE(0XF8006064, 0x00021FE0U ,0x00020000U), + // .. .. reg_ddrc_wrlvl_ww = 0x41 + // .. .. ==> 0XF8006068[7:0] = 0x00000041U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000041U + // .. .. reg_ddrc_rdlvl_rr = 0x41 + // .. .. ==> 0XF8006068[15:8] = 0x00000041U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00004100U + // .. .. reg_ddrc_dfi_t_wlmrd = 0x28 + // .. .. ==> 0XF8006068[25:16] = 0x00000028U + // .. .. ==> MASK : 0x03FF0000U VAL : 0x00280000U + // .. .. + EMIT_MASKWRITE(0XF8006068, 0x03FFFFFFU ,0x00284141U), + // .. .. dfi_t_ctrlupd_interval_min_x1024 = 0x10 + // .. .. ==> 0XF800606C[7:0] = 0x00000010U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000010U + // .. .. dfi_t_ctrlupd_interval_max_x1024 = 0x16 + // .. .. ==> 0XF800606C[15:8] = 0x00000016U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00001600U + // .. .. + EMIT_MASKWRITE(0XF800606C, 0x0000FFFFU ,0x00001610U), + // .. .. reg_ddrc_dfi_t_ctrl_delay = 0x1 + // .. .. ==> 0XF8006078[3:0] = 0x00000001U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000001U + // .. .. reg_ddrc_dfi_t_dram_clk_disable = 0x1 + // .. .. ==> 0XF8006078[7:4] = 0x00000001U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000010U + // .. .. reg_ddrc_dfi_t_dram_clk_enable = 0x1 + // .. .. ==> 0XF8006078[11:8] = 0x00000001U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000100U + // .. .. reg_ddrc_t_cksre = 0x6 + // .. .. ==> 0XF8006078[15:12] = 0x00000006U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00006000U + // .. .. reg_ddrc_t_cksrx = 0x6 + // .. .. ==> 0XF8006078[19:16] = 0x00000006U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00060000U + // .. .. reg_ddrc_t_ckesr = 0x4 + // .. .. ==> 0XF8006078[25:20] = 0x00000004U + // .. .. ==> MASK : 0x03F00000U VAL : 0x00400000U + // .. .. + EMIT_MASKWRITE(0XF8006078, 0x03FFFFFFU ,0x00466111U), + // .. .. reg_ddrc_t_ckpde = 0x2 + // .. .. ==> 0XF800607C[3:0] = 0x00000002U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000002U + // .. .. reg_ddrc_t_ckpdx = 0x2 + // .. .. ==> 0XF800607C[7:4] = 0x00000002U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000020U + // .. .. reg_ddrc_t_ckdpde = 0x2 + // .. .. ==> 0XF800607C[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. reg_ddrc_t_ckdpdx = 0x2 + // .. .. ==> 0XF800607C[15:12] = 0x00000002U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00002000U + // .. .. reg_ddrc_t_ckcsx = 0x3 + // .. .. ==> 0XF800607C[19:16] = 0x00000003U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00030000U + // .. .. + EMIT_MASKWRITE(0XF800607C, 0x000FFFFFU ,0x00032222U), + // .. .. refresh_timer0_start_value_x32 = 0x0 + // .. .. ==> 0XF80060A0[11:0] = 0x00000000U + // .. .. ==> MASK : 0x00000FFFU VAL : 0x00000000U + // .. .. refresh_timer1_start_value_x32 = 0x8 + // .. .. ==> 0XF80060A0[23:12] = 0x00000008U + // .. .. ==> MASK : 0x00FFF000U VAL : 0x00008000U + // .. .. + EMIT_MASKWRITE(0XF80060A0, 0x00FFFFFFU ,0x00008000U), + // .. .. reg_ddrc_dis_auto_zq = 0x0 + // .. .. ==> 0XF80060A4[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_ddr3 = 0x1 + // .. .. ==> 0XF80060A4[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. reg_ddrc_t_mod = 0x200 + // .. .. ==> 0XF80060A4[11:2] = 0x00000200U + // .. .. ==> MASK : 0x00000FFCU VAL : 0x00000800U + // .. .. reg_ddrc_t_zq_long_nop = 0x200 + // .. .. ==> 0XF80060A4[21:12] = 0x00000200U + // .. .. ==> MASK : 0x003FF000U VAL : 0x00200000U + // .. .. reg_ddrc_t_zq_short_nop = 0x40 + // .. .. ==> 0XF80060A4[31:22] = 0x00000040U + // .. .. ==> MASK : 0xFFC00000U VAL : 0x10000000U + // .. .. + EMIT_MASKWRITE(0XF80060A4, 0xFFFFFFFFU ,0x10200802U), + // .. .. t_zq_short_interval_x1024 = 0xc845 + // .. .. ==> 0XF80060A8[19:0] = 0x0000C845U + // .. .. ==> MASK : 0x000FFFFFU VAL : 0x0000C845U + // .. .. dram_rstn_x1024 = 0x67 + // .. .. ==> 0XF80060A8[27:20] = 0x00000067U + // .. .. ==> MASK : 0x0FF00000U VAL : 0x06700000U + // .. .. + EMIT_MASKWRITE(0XF80060A8, 0x0FFFFFFFU ,0x0670C845U), + // .. .. deeppowerdown_en = 0x0 + // .. .. ==> 0XF80060AC[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. deeppowerdown_to_x1024 = 0xff + // .. .. ==> 0XF80060AC[8:1] = 0x000000FFU + // .. .. ==> MASK : 0x000001FEU VAL : 0x000001FEU + // .. .. + EMIT_MASKWRITE(0XF80060AC, 0x000001FFU ,0x000001FEU), + // .. .. dfi_wrlvl_max_x1024 = 0xfff + // .. .. ==> 0XF80060B0[11:0] = 0x00000FFFU + // .. .. ==> MASK : 0x00000FFFU VAL : 0x00000FFFU + // .. .. dfi_rdlvl_max_x1024 = 0xfff + // .. .. ==> 0XF80060B0[23:12] = 0x00000FFFU + // .. .. ==> MASK : 0x00FFF000U VAL : 0x00FFF000U + // .. .. ddrc_reg_twrlvl_max_error = 0x0 + // .. .. ==> 0XF80060B0[24:24] = 0x00000000U + // .. .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. .. ddrc_reg_trdlvl_max_error = 0x0 + // .. .. ==> 0XF80060B0[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. reg_ddrc_dfi_wr_level_en = 0x1 + // .. .. ==> 0XF80060B0[26:26] = 0x00000001U + // .. .. ==> MASK : 0x04000000U VAL : 0x04000000U + // .. .. reg_ddrc_dfi_rd_dqs_gate_level = 0x1 + // .. .. ==> 0XF80060B0[27:27] = 0x00000001U + // .. .. ==> MASK : 0x08000000U VAL : 0x08000000U + // .. .. reg_ddrc_dfi_rd_data_eye_train = 0x1 + // .. .. ==> 0XF80060B0[28:28] = 0x00000001U + // .. .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. .. + EMIT_MASKWRITE(0XF80060B0, 0x1FFFFFFFU ,0x1CFFFFFFU), + // .. .. reg_ddrc_2t_delay = 0x0 + // .. .. ==> 0XF80060B4[8:0] = 0x00000000U + // .. .. ==> MASK : 0x000001FFU VAL : 0x00000000U + // .. .. reg_ddrc_skip_ocd = 0x1 + // .. .. ==> 0XF80060B4[9:9] = 0x00000001U + // .. .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. .. reg_ddrc_dis_pre_bypass = 0x0 + // .. .. ==> 0XF80060B4[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80060B4, 0x000007FFU ,0x00000200U), + // .. .. reg_ddrc_dfi_t_rddata_en = 0x6 + // .. .. ==> 0XF80060B8[4:0] = 0x00000006U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000006U + // .. .. reg_ddrc_dfi_t_ctrlup_min = 0x3 + // .. .. ==> 0XF80060B8[14:5] = 0x00000003U + // .. .. ==> MASK : 0x00007FE0U VAL : 0x00000060U + // .. .. reg_ddrc_dfi_t_ctrlup_max = 0x40 + // .. .. ==> 0XF80060B8[24:15] = 0x00000040U + // .. .. ==> MASK : 0x01FF8000U VAL : 0x00200000U + // .. .. + EMIT_MASKWRITE(0XF80060B8, 0x01FFFFFFU ,0x00200066U), + // .. .. Clear_Uncorrectable_DRAM_ECC_error = 1 + // .. .. ==> 0XF80060C4[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. Clear_Correctable_DRAM_ECC_error = 1 + // .. .. ==> 0XF80060C4[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. + EMIT_MASKWRITE(0XF80060C4, 0x00000003U ,0x00000003U), + // .. FINISH: DDR INITIALIZATION + // .. Clear_Uncorrectable_DRAM_ECC_error = 0x0 + // .. ==> 0XF80060C4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. Clear_Correctable_DRAM_ECC_error = 0x0 + // .. ==> 0XF80060C4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060C4, 0x00000003U ,0x00000000U), + // .. CORR_ECC_LOG_VALID = 0x0 + // .. ==> 0XF80060C8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. ECC_CORRECTED_BIT_NUM = 0x0 + // .. ==> 0XF80060C8[7:1] = 0x00000000U + // .. ==> MASK : 0x000000FEU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060C8, 0x000000FFU ,0x00000000U), + // .. UNCORR_ECC_LOG_VALID = 0x0 + // .. ==> 0XF80060DC[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060DC, 0x00000001U ,0x00000000U), + // .. STAT_NUM_CORR_ERR = 0x0 + // .. ==> 0XF80060F0[15:8] = 0x00000000U + // .. ==> MASK : 0x0000FF00U VAL : 0x00000000U + // .. STAT_NUM_UNCORR_ERR = 0x0 + // .. ==> 0XF80060F0[7:0] = 0x00000000U + // .. ==> MASK : 0x000000FFU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80060F0, 0x0000FFFFU ,0x00000000U), + // .. reg_ddrc_ecc_mode = 0x0 + // .. ==> 0XF80060F4[2:0] = 0x00000000U + // .. ==> MASK : 0x00000007U VAL : 0x00000000U + // .. reg_ddrc_dis_scrub = 0x1 + // .. ==> 0XF80060F4[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. + EMIT_MASKWRITE(0XF80060F4, 0x0000000FU ,0x00000008U), + // .. reg_phy_dif_on = 0x0 + // .. ==> 0XF8006114[3:0] = 0x00000000U + // .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. reg_phy_dif_off = 0x0 + // .. ==> 0XF8006114[7:4] = 0x00000000U + // .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006114, 0x000000FFU ,0x00000000U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF8006118[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF8006118[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF8006118[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF8006118[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF8006118[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF8006118[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF8006118[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF8006118[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF8006118[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF8006118, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF800611C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF800611C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF800611C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF800611C[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF800611C[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF800611C[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF800611C[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF800611C[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF800611C[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF800611C, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF8006120[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF8006120[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF8006120[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF8006120[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF8006120[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF8006120[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF8006120[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF8006120[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF8006120[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF8006120[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF8006120[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF8006120[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF8006120[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF8006120[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF8006120[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF8006120[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF8006120[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF8006120[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF8006120, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_data_slice_in_use = 0x1 + // .. ==> 0XF8006124[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_phy_rdlvl_inc_mode = 0x0 + // .. ==> 0XF8006124[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_gatelvl_inc_mode = 0x0 + // .. ==> 0XF8006124[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_wrlvl_inc_mode = 0x0 + // .. ==> 0XF8006124[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_board_lpbk_tx = 0x0 + // .. ==> 0XF8006124[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_board_lpbk_rx = 0x0 + // .. ==> 0XF8006124[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. reg_phy_bist_shift_dq = 0x0 + // .. ==> 0XF8006124[14:6] = 0x00000000U + // .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. reg_phy_bist_err_clr = 0x0 + // .. ==> 0XF8006124[23:15] = 0x00000000U + // .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. reg_phy_dq_offset = 0x40 + // .. ==> 0XF8006124[30:24] = 0x00000040U + // .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. + EMIT_MASKWRITE(0XF8006124, 0x7FFFFFFFU ,0x40000001U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF800612C[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x8f + // .. ==> 0XF800612C[19:10] = 0x0000008FU + // .. ==> MASK : 0x000FFC00U VAL : 0x00023C00U + // .. + EMIT_MASKWRITE(0XF800612C, 0x000FFFFFU ,0x00023C00U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF8006130[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x8a + // .. ==> 0XF8006130[19:10] = 0x0000008AU + // .. ==> MASK : 0x000FFC00U VAL : 0x00022800U + // .. + EMIT_MASKWRITE(0XF8006130, 0x000FFFFFU ,0x00022800U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF8006134[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x8b + // .. ==> 0XF8006134[19:10] = 0x0000008BU + // .. ==> MASK : 0x000FFC00U VAL : 0x00022C00U + // .. + EMIT_MASKWRITE(0XF8006134, 0x000FFFFFU ,0x00022C00U), + // .. reg_phy_wrlvl_init_ratio = 0x0 + // .. ==> 0XF8006138[9:0] = 0x00000000U + // .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. reg_phy_gatelvl_init_ratio = 0x92 + // .. ==> 0XF8006138[19:10] = 0x00000092U + // .. ==> MASK : 0x000FFC00U VAL : 0x00024800U + // .. + EMIT_MASKWRITE(0XF8006138, 0x000FFFFFU ,0x00024800U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF8006140[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF8006140[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF8006140[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006140, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF8006144[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF8006144[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF8006144[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006144, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF8006148[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF8006148[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF8006148[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006148, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. ==> 0XF800614C[9:0] = 0x00000035U + // .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. reg_phy_rd_dqs_slave_force = 0x0 + // .. ==> 0XF800614C[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. ==> 0XF800614C[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800614C, 0x000FFFFFU ,0x00000035U), + // .. reg_phy_wr_dqs_slave_ratio = 0x77 + // .. ==> 0XF8006154[9:0] = 0x00000077U + // .. ==> MASK : 0x000003FFU VAL : 0x00000077U + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF8006154[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF8006154[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006154, 0x000FFFFFU ,0x00000077U), + // .. reg_phy_wr_dqs_slave_ratio = 0x7c + // .. ==> 0XF8006158[9:0] = 0x0000007CU + // .. ==> MASK : 0x000003FFU VAL : 0x0000007CU + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF8006158[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF8006158[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006158, 0x000FFFFFU ,0x0000007CU), + // .. reg_phy_wr_dqs_slave_ratio = 0x7c + // .. ==> 0XF800615C[9:0] = 0x0000007CU + // .. ==> MASK : 0x000003FFU VAL : 0x0000007CU + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF800615C[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF800615C[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800615C, 0x000FFFFFU ,0x0000007CU), + // .. reg_phy_wr_dqs_slave_ratio = 0x75 + // .. ==> 0XF8006160[9:0] = 0x00000075U + // .. ==> MASK : 0x000003FFU VAL : 0x00000075U + // .. reg_phy_wr_dqs_slave_force = 0x0 + // .. ==> 0XF8006160[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. ==> 0XF8006160[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006160, 0x000FFFFFU ,0x00000075U), + // .. reg_phy_fifo_we_slave_ratio = 0xe4 + // .. ==> 0XF8006168[10:0] = 0x000000E4U + // .. ==> MASK : 0x000007FFU VAL : 0x000000E4U + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF8006168[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF8006168[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006168, 0x001FFFFFU ,0x000000E4U), + // .. reg_phy_fifo_we_slave_ratio = 0xdf + // .. ==> 0XF800616C[10:0] = 0x000000DFU + // .. ==> MASK : 0x000007FFU VAL : 0x000000DFU + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF800616C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF800616C[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800616C, 0x001FFFFFU ,0x000000DFU), + // .. reg_phy_fifo_we_slave_ratio = 0xe0 + // .. ==> 0XF8006170[10:0] = 0x000000E0U + // .. ==> MASK : 0x000007FFU VAL : 0x000000E0U + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF8006170[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF8006170[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006170, 0x001FFFFFU ,0x000000E0U), + // .. reg_phy_fifo_we_slave_ratio = 0xe7 + // .. ==> 0XF8006174[10:0] = 0x000000E7U + // .. ==> MASK : 0x000007FFU VAL : 0x000000E7U + // .. reg_phy_fifo_we_in_force = 0x0 + // .. ==> 0XF8006174[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reg_phy_fifo_we_in_delay = 0x0 + // .. ==> 0XF8006174[20:12] = 0x00000000U + // .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006174, 0x001FFFFFU ,0x000000E7U), + // .. reg_phy_wr_data_slave_ratio = 0xb7 + // .. ==> 0XF800617C[9:0] = 0x000000B7U + // .. ==> MASK : 0x000003FFU VAL : 0x000000B7U + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF800617C[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF800617C[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800617C, 0x000FFFFFU ,0x000000B7U), + // .. reg_phy_wr_data_slave_ratio = 0xbc + // .. ==> 0XF8006180[9:0] = 0x000000BCU + // .. ==> MASK : 0x000003FFU VAL : 0x000000BCU + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF8006180[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF8006180[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006180, 0x000FFFFFU ,0x000000BCU), + // .. reg_phy_wr_data_slave_ratio = 0xbc + // .. ==> 0XF8006184[9:0] = 0x000000BCU + // .. ==> MASK : 0x000003FFU VAL : 0x000000BCU + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF8006184[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF8006184[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006184, 0x000FFFFFU ,0x000000BCU), + // .. reg_phy_wr_data_slave_ratio = 0xb5 + // .. ==> 0XF8006188[9:0] = 0x000000B5U + // .. ==> MASK : 0x000003FFU VAL : 0x000000B5U + // .. reg_phy_wr_data_slave_force = 0x0 + // .. ==> 0XF8006188[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reg_phy_wr_data_slave_delay = 0x0 + // .. ==> 0XF8006188[19:11] = 0x00000000U + // .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006188, 0x000FFFFFU ,0x000000B5U), + // .. reg_phy_loopback = 0x0 + // .. ==> 0XF8006190[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. reg_phy_bl2 = 0x0 + // .. ==> 0XF8006190[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_phy_at_spd_atpg = 0x0 + // .. ==> 0XF8006190[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_phy_bist_enable = 0x0 + // .. ==> 0XF8006190[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. reg_phy_bist_force_err = 0x0 + // .. ==> 0XF8006190[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. reg_phy_bist_mode = 0x0 + // .. ==> 0XF8006190[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. reg_phy_invert_clkout = 0x1 + // .. ==> 0XF8006190[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. reg_phy_all_dq_mpr_rd_resp = 0x0 + // .. ==> 0XF8006190[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. reg_phy_sel_logic = 0x0 + // .. ==> 0XF8006190[9:9] = 0x00000000U + // .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. reg_phy_ctrl_slave_ratio = 0x100 + // .. ==> 0XF8006190[19:10] = 0x00000100U + // .. ==> MASK : 0x000FFC00U VAL : 0x00040000U + // .. reg_phy_ctrl_slave_force = 0x0 + // .. ==> 0XF8006190[20:20] = 0x00000000U + // .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. reg_phy_ctrl_slave_delay = 0x0 + // .. ==> 0XF8006190[27:21] = 0x00000000U + // .. ==> MASK : 0x0FE00000U VAL : 0x00000000U + // .. reg_phy_use_rank0_delays = 0x1 + // .. ==> 0XF8006190[28:28] = 0x00000001U + // .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. reg_phy_lpddr = 0x0 + // .. ==> 0XF8006190[29:29] = 0x00000000U + // .. ==> MASK : 0x20000000U VAL : 0x00000000U + // .. reg_phy_cmd_latency = 0x0 + // .. ==> 0XF8006190[30:30] = 0x00000000U + // .. ==> MASK : 0x40000000U VAL : 0x00000000U + // .. reg_phy_int_lpbk = 0x0 + // .. ==> 0XF8006190[31:31] = 0x00000000U + // .. ==> MASK : 0x80000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006190, 0xFFFFFFFFU ,0x10040080U), + // .. reg_phy_wr_rl_delay = 0x2 + // .. ==> 0XF8006194[4:0] = 0x00000002U + // .. ==> MASK : 0x0000001FU VAL : 0x00000002U + // .. reg_phy_rd_rl_delay = 0x4 + // .. ==> 0XF8006194[9:5] = 0x00000004U + // .. ==> MASK : 0x000003E0U VAL : 0x00000080U + // .. reg_phy_dll_lock_diff = 0xf + // .. ==> 0XF8006194[13:10] = 0x0000000FU + // .. ==> MASK : 0x00003C00U VAL : 0x00003C00U + // .. reg_phy_use_wr_level = 0x1 + // .. ==> 0XF8006194[14:14] = 0x00000001U + // .. ==> MASK : 0x00004000U VAL : 0x00004000U + // .. reg_phy_use_rd_dqs_gate_level = 0x1 + // .. ==> 0XF8006194[15:15] = 0x00000001U + // .. ==> MASK : 0x00008000U VAL : 0x00008000U + // .. reg_phy_use_rd_data_eye_level = 0x1 + // .. ==> 0XF8006194[16:16] = 0x00000001U + // .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. reg_phy_dis_calib_rst = 0x0 + // .. ==> 0XF8006194[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_phy_ctrl_slave_delay = 0x0 + // .. ==> 0XF8006194[19:18] = 0x00000000U + // .. ==> MASK : 0x000C0000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006194, 0x000FFFFFU ,0x0001FC82U), + // .. reg_arb_page_addr_mask = 0x0 + // .. ==> 0XF8006204[31:0] = 0x00000000U + // .. ==> MASK : 0xFFFFFFFFU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006204, 0xFFFFFFFFU ,0x00000000U), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF8006208[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF8006208[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF8006208[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF8006208[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF8006208[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF8006208, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF800620C[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF800620C[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF800620C[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF800620C[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF800620C[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF800620C, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF8006210[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF8006210[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF8006210[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF8006210[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF8006210[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF8006210, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_wr_portn = 0x3ff + // .. ==> 0XF8006214[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_wr_portn = 0x0 + // .. ==> 0XF8006214[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. ==> 0XF8006214[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. ==> 0XF8006214[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_dis_rmw_portn = 0x1 + // .. ==> 0XF8006214[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XF8006214, 0x000F03FFU ,0x000803FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF8006218[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF8006218[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF8006218[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF8006218[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF8006218[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006218, 0x000F03FFU ,0x000003FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF800621C[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF800621C[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF800621C[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF800621C[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF800621C[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800621C, 0x000F03FFU ,0x000003FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF8006220[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF8006220[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF8006220[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF8006220[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF8006220[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006220, 0x000F03FFU ,0x000003FFU), + // .. reg_arb_pri_rd_portn = 0x3ff + // .. ==> 0XF8006224[9:0] = 0x000003FFU + // .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. reg_arb_disable_aging_rd_portn = 0x0 + // .. ==> 0XF8006224[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. ==> 0XF8006224[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. ==> 0XF8006224[18:18] = 0x00000000U + // .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. reg_arb_set_hpr_rd_portn = 0x0 + // .. ==> 0XF8006224[19:19] = 0x00000000U + // .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006224, 0x000F03FFU ,0x000003FFU), + // .. reg_ddrc_lpddr2 = 0x0 + // .. ==> 0XF80062A8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. reg_ddrc_per_bank_refresh = 0x0 + // .. ==> 0XF80062A8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_ddrc_derate_enable = 0x0 + // .. ==> 0XF80062A8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. reg_ddrc_mr4_margin = 0x0 + // .. ==> 0XF80062A8[11:4] = 0x00000000U + // .. ==> MASK : 0x00000FF0U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80062A8, 0x00000FF7U ,0x00000000U), + // .. reg_ddrc_mr4_read_interval = 0x0 + // .. ==> 0XF80062AC[31:0] = 0x00000000U + // .. ==> MASK : 0xFFFFFFFFU VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80062AC, 0xFFFFFFFFU ,0x00000000U), + // .. reg_ddrc_min_stable_clock_x1 = 0x5 + // .. ==> 0XF80062B0[3:0] = 0x00000005U + // .. ==> MASK : 0x0000000FU VAL : 0x00000005U + // .. reg_ddrc_idle_after_reset_x32 = 0x12 + // .. ==> 0XF80062B0[11:4] = 0x00000012U + // .. ==> MASK : 0x00000FF0U VAL : 0x00000120U + // .. reg_ddrc_t_mrw = 0x5 + // .. ==> 0XF80062B0[21:12] = 0x00000005U + // .. ==> MASK : 0x003FF000U VAL : 0x00005000U + // .. + EMIT_MASKWRITE(0XF80062B0, 0x003FFFFFU ,0x00005125U), + // .. reg_ddrc_max_auto_init_x1024 = 0xa6 + // .. ==> 0XF80062B4[7:0] = 0x000000A6U + // .. ==> MASK : 0x000000FFU VAL : 0x000000A6U + // .. reg_ddrc_dev_zqinit_x32 = 0x12 + // .. ==> 0XF80062B4[17:8] = 0x00000012U + // .. ==> MASK : 0x0003FF00U VAL : 0x00001200U + // .. + EMIT_MASKWRITE(0XF80062B4, 0x0003FFFFU ,0x000012A6U), + // .. START: POLL ON DCI STATUS + // .. DONE = 1 + // .. ==> 0XF8000B74[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKPOLL(0XF8000B74, 0x00002000U), + // .. FINISH: POLL ON DCI STATUS + // .. START: UNLOCK DDR + // .. reg_ddrc_soft_rstb = 0x1 + // .. ==> 0XF8006000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. reg_ddrc_powerdown_en = 0x0 + // .. ==> 0XF8006000[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. reg_ddrc_data_bus_width = 0x0 + // .. ==> 0XF8006000[3:2] = 0x00000000U + // .. ==> MASK : 0x0000000CU VAL : 0x00000000U + // .. reg_ddrc_burst8_refresh = 0x0 + // .. ==> 0XF8006000[6:4] = 0x00000000U + // .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. reg_ddrc_rdwr_idle_gap = 1 + // .. ==> 0XF8006000[13:7] = 0x00000001U + // .. ==> MASK : 0x00003F80U VAL : 0x00000080U + // .. reg_ddrc_dis_rd_bypass = 0x0 + // .. ==> 0XF8006000[14:14] = 0x00000000U + // .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. reg_ddrc_dis_act_bypass = 0x0 + // .. ==> 0XF8006000[15:15] = 0x00000000U + // .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. reg_ddrc_dis_auto_refresh = 0x0 + // .. ==> 0XF8006000[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8006000, 0x0001FFFFU ,0x00000081U), + // .. FINISH: UNLOCK DDR + // .. START: CHECK DDR STATUS + // .. ddrc_reg_operating_mode = 1 + // .. ==> 0XF8006054[2:0] = 0x00000001U + // .. ==> MASK : 0x00000007U VAL : 0x00000001U + // .. + EMIT_MASKPOLL(0XF8006054, 0x00000007U), + // .. FINISH: CHECK DDR STATUS + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_mio_init_data_2_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: OCM REMAPPING + // .. VREF_EN = 0x1 + // .. ==> 0XF8000B00[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. VREF_PULLUP_EN = 0x0 + // .. ==> 0XF8000B00[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. CLK_PULLUP_EN = 0x0 + // .. ==> 0XF8000B00[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. SRSTN_PULLUP_EN = 0x0 + // .. ==> 0XF8000B00[9:9] = 0x00000000U + // .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B00, 0x00000303U ,0x00000001U), + // .. FINISH: OCM REMAPPING + // .. START: DDRIOB SETTINGS + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B40[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B40[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B40[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B40[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCR_TYPE = 0x0 + // .. ==> 0XF8000B40[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B40[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B40[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B40[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B40[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B40, 0x00000FFFU ,0x00000600U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B44[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B44[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B44[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B44[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCR_TYPE = 0x0 + // .. ==> 0XF8000B44[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B44[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B44[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B44[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B44[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B44, 0x00000FFFU ,0x00000600U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B48[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x1 + // .. ==> 0XF8000B48[2:1] = 0x00000001U + // .. ==> MASK : 0x00000006U VAL : 0x00000002U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B48[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B48[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B48[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B48[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B48[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B48[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B48[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B48, 0x00000FFFU ,0x00000672U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B4C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x1 + // .. ==> 0XF8000B4C[2:1] = 0x00000001U + // .. ==> MASK : 0x00000006U VAL : 0x00000002U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B4C[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B4C[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B4C[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B4C[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B4C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B4C[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B4C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B4C, 0x00000FFFU ,0x00000672U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B50[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x2 + // .. ==> 0XF8000B50[2:1] = 0x00000002U + // .. ==> MASK : 0x00000006U VAL : 0x00000004U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B50[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B50[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B50[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B50[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B50[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B50[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B50[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B50, 0x00000FFFU ,0x00000674U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B54[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x2 + // .. ==> 0XF8000B54[2:1] = 0x00000002U + // .. ==> MASK : 0x00000006U VAL : 0x00000004U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B54[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B54[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCR_TYPE = 0x3 + // .. ==> 0XF8000B54[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B54[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B54[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B54[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B54[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B54, 0x00000FFFU ,0x00000674U), + // .. INP_POWER = 0x0 + // .. ==> 0XF8000B58[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B58[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE = 0x0 + // .. ==> 0XF8000B58[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B58[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCR_TYPE = 0x0 + // .. ==> 0XF8000B58[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B58[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B58[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B58[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B58[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B58, 0x00000FFFU ,0x00000600U), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B5C[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B5C[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x1a + // .. ==> 0XF8000B5C[18:14] = 0x0000001AU + // .. ==> MASK : 0x0007C000U VAL : 0x00068000U + // .. SLEW_N = 0x1a + // .. ==> 0XF8000B5C[23:19] = 0x0000001AU + // .. ==> MASK : 0x00F80000U VAL : 0x00D00000U + // .. GTL = 0x0 + // .. ==> 0XF8000B5C[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B5C[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B5C, 0xFFFFFFFFU ,0x00D6861CU), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B60[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B60[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x6 + // .. ==> 0XF8000B60[18:14] = 0x00000006U + // .. ==> MASK : 0x0007C000U VAL : 0x00018000U + // .. SLEW_N = 0x1f + // .. ==> 0XF8000B60[23:19] = 0x0000001FU + // .. ==> MASK : 0x00F80000U VAL : 0x00F80000U + // .. GTL = 0x0 + // .. ==> 0XF8000B60[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B60[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B60, 0xFFFFFFFFU ,0x00F9861CU), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B64[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B64[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x6 + // .. ==> 0XF8000B64[18:14] = 0x00000006U + // .. ==> MASK : 0x0007C000U VAL : 0x00018000U + // .. SLEW_N = 0x1f + // .. ==> 0XF8000B64[23:19] = 0x0000001FU + // .. ==> MASK : 0x00F80000U VAL : 0x00F80000U + // .. GTL = 0x0 + // .. ==> 0XF8000B64[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B64[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B64, 0xFFFFFFFFU ,0x00F9861CU), + // .. DRIVE_P = 0x1c + // .. ==> 0XF8000B68[6:0] = 0x0000001CU + // .. ==> MASK : 0x0000007FU VAL : 0x0000001CU + // .. DRIVE_N = 0xc + // .. ==> 0XF8000B68[13:7] = 0x0000000CU + // .. ==> MASK : 0x00003F80U VAL : 0x00000600U + // .. SLEW_P = 0x1a + // .. ==> 0XF8000B68[18:14] = 0x0000001AU + // .. ==> MASK : 0x0007C000U VAL : 0x00068000U + // .. SLEW_N = 0x1a + // .. ==> 0XF8000B68[23:19] = 0x0000001AU + // .. ==> MASK : 0x00F80000U VAL : 0x00D00000U + // .. GTL = 0x0 + // .. ==> 0XF8000B68[26:24] = 0x00000000U + // .. ==> MASK : 0x07000000U VAL : 0x00000000U + // .. RTERM = 0x0 + // .. ==> 0XF8000B68[31:27] = 0x00000000U + // .. ==> MASK : 0xF8000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B68, 0xFFFFFFFFU ,0x00D6861CU), + // .. VREF_INT_EN = 0x0 + // .. ==> 0XF8000B6C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. VREF_SEL = 0x0 + // .. ==> 0XF8000B6C[4:1] = 0x00000000U + // .. ==> MASK : 0x0000001EU VAL : 0x00000000U + // .. VREF_EXT_EN = 0x3 + // .. ==> 0XF8000B6C[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. VREF_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[8:7] = 0x00000000U + // .. ==> MASK : 0x00000180U VAL : 0x00000000U + // .. REFIO_EN = 0x1 + // .. ==> 0XF8000B6C[9:9] = 0x00000001U + // .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. REFIO_TEST = 0x3 + // .. ==> 0XF8000B6C[11:10] = 0x00000003U + // .. ==> MASK : 0x00000C00U VAL : 0x00000C00U + // .. REFIO_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DRST_B_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. CKE_PULLUP_EN = 0x0 + // .. ==> 0XF8000B6C[14:14] = 0x00000000U + // .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B6C, 0x00007FFFU ,0x00000E60U), + // .. .. START: ASSERT RESET + // .. .. RESET = 1 + // .. .. ==> 0XF8000B70[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. VRN_OUT = 0x1 + // .. .. ==> 0XF8000B70[5:5] = 0x00000001U + // .. .. ==> MASK : 0x00000020U VAL : 0x00000020U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x00000021U ,0x00000021U), + // .. .. FINISH: ASSERT RESET + // .. .. START: DEASSERT RESET + // .. .. RESET = 0 + // .. .. ==> 0XF8000B70[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. VRN_OUT = 0x1 + // .. .. ==> 0XF8000B70[5:5] = 0x00000001U + // .. .. ==> MASK : 0x00000020U VAL : 0x00000020U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x00000021U ,0x00000020U), + // .. .. FINISH: DEASSERT RESET + // .. .. RESET = 0x1 + // .. .. ==> 0XF8000B70[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. ENABLE = 0x1 + // .. .. ==> 0XF8000B70[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. VRP_TRI = 0x0 + // .. .. ==> 0XF8000B70[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. VRN_TRI = 0x0 + // .. .. ==> 0XF8000B70[3:3] = 0x00000000U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. .. VRP_OUT = 0x0 + // .. .. ==> 0XF8000B70[4:4] = 0x00000000U + // .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. VRN_OUT = 0x1 + // .. .. ==> 0XF8000B70[5:5] = 0x00000001U + // .. .. ==> MASK : 0x00000020U VAL : 0x00000020U + // .. .. NREF_OPT1 = 0x0 + // .. .. ==> 0XF8000B70[7:6] = 0x00000000U + // .. .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. .. NREF_OPT2 = 0x0 + // .. .. ==> 0XF8000B70[10:8] = 0x00000000U + // .. .. ==> MASK : 0x00000700U VAL : 0x00000000U + // .. .. NREF_OPT4 = 0x1 + // .. .. ==> 0XF8000B70[13:11] = 0x00000001U + // .. .. ==> MASK : 0x00003800U VAL : 0x00000800U + // .. .. PREF_OPT1 = 0x0 + // .. .. ==> 0XF8000B70[16:14] = 0x00000000U + // .. .. ==> MASK : 0x0001C000U VAL : 0x00000000U + // .. .. PREF_OPT2 = 0x0 + // .. .. ==> 0XF8000B70[19:17] = 0x00000000U + // .. .. ==> MASK : 0x000E0000U VAL : 0x00000000U + // .. .. UPDATE_CONTROL = 0x0 + // .. .. ==> 0XF8000B70[20:20] = 0x00000000U + // .. .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. .. INIT_COMPLETE = 0x0 + // .. .. ==> 0XF8000B70[21:21] = 0x00000000U + // .. .. ==> MASK : 0x00200000U VAL : 0x00000000U + // .. .. TST_CLK = 0x0 + // .. .. ==> 0XF8000B70[22:22] = 0x00000000U + // .. .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. .. TST_HLN = 0x0 + // .. .. ==> 0XF8000B70[23:23] = 0x00000000U + // .. .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. .. TST_HLP = 0x0 + // .. .. ==> 0XF8000B70[24:24] = 0x00000000U + // .. .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. .. TST_RST = 0x0 + // .. .. ==> 0XF8000B70[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. INT_DCI_EN = 0x0 + // .. .. ==> 0XF8000B70[26:26] = 0x00000000U + // .. .. ==> MASK : 0x04000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x07FFFFFFU ,0x00000823U), + // .. FINISH: DDRIOB SETTINGS + // .. START: MIO PROGRAMMING + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000700[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000700[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000700[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000700[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000700[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000700[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000700[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000700[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000700[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000700, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000704[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000704[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000704[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000704[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000704[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000704[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000704[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000704[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000704[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000704, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000708[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000708[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000708[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000708[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000708[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000708[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000708[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000708[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000708[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000708, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800070C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF800070C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800070C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800070C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800070C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800070C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF800070C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800070C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800070C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800070C, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000710[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000710[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000710[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000710[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000710[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000710[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000710[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000710[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000710[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000710, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000714[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000714[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000714[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000714[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000714[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000714[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000714[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000714[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000714[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000714, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000718[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000718[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000718[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000718[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000718[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000718[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000718[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000718[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000718[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000718, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800071C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800071C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800071C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800071C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800071C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF800071C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800071C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800071C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800071C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800071C, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000720[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000720[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000720[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000720[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000720[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000720[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000720[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000720[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000720[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000720, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000724[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000724[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000724[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000724[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000724[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000724[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000724[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000724[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000724[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000724, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000728[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000728[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000728[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000728[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000728[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U + // .. Speed = 0 + // .. ==> 0XF8000728[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000728[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 1 + // .. ==> 0XF8000728[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000728[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000728, 0x00003FFFU ,0x00001640U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800072C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800072C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800072C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800072C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF800072C[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U + // .. Speed = 0 + // .. ==> 0XF800072C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800072C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 1 + // .. ==> 0XF800072C[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. DisableRcvr = 0 + // .. ==> 0XF800072C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800072C, 0x00003FFFU ,0x00001640U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000730[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000730[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000730[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000730[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000730[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000730[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000730[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000730[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000730[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000734[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000734[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000734[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000734[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000734[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000734[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000734[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000734[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000734[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000738[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000738[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000738[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000738[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000738[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000738[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000738[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000738[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000738[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000738, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800073C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800073C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800073C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800073C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800073C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF800073C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800073C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800073C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800073C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800073C, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000740[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000740[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000740[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000740[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000740[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000740[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000740[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000740[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000740[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000740, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000744[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000744[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000744[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000744[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000744[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000744[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000744[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000744[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000744[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000744, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000748[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000748[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000748[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000748[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000748[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000748[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000748[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000748[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000748[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000748, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800074C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF800074C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800074C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800074C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800074C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800074C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800074C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800074C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF800074C[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF800074C, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000750[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000750[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000750[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000750[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000750[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000750[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000750[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000750[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000750[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000750, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000754[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000754[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000754[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000754[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000754[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000754[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000754[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000754[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000754[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000754, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000758[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000758[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000758[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000758[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000758[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000758[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000758[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000758[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000758[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000758, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800075C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF800075C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800075C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800075C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800075C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800075C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800075C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800075C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800075C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800075C, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000760[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000760[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000760[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000760[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000760[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000760[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000760[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000760[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000760[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000760, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000764[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000764[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000764[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000764[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000764[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000764[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000764[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000764[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000764[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000764, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000768[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000768[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000768[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000768[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000768[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000768[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000768[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000768[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000768[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000768, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800076C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF800076C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800076C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800076C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800076C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800076C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800076C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800076C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800076C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800076C, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000770[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000770[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000770[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000770[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000770[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000770[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000770[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000770[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000770[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000770, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000774[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF8000774[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000774[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000774[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000774[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000774[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000774[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000774[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000774[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000774, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000778[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000778[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000778[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000778[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000778[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000778[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000778[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000778[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000778[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000778, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800077C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF800077C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800077C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800077C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800077C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800077C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800077C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800077C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800077C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800077C, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000780[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000780[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000780[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000780[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000780[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000780[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000780[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000780[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000780[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000780, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000784[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000784[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000784[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000784[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000784[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000784[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000784[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000784[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000784[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000784, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000788[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000788[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000788[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000788[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000788[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000788[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000788[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000788[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000788[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000788, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800078C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800078C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800078C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800078C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800078C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800078C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800078C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800078C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800078C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800078C, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000790[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF8000790[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000790[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000790[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000790[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000790[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000790[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000790[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000790[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000790, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000794[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000794[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000794[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000794[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000794[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000794[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000794[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000794[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000794[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000794, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000798[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000798[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000798[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000798[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000798[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000798[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000798[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000798[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000798[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000798, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800079C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800079C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800079C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800079C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800079C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800079C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800079C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800079C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800079C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800079C, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A0[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A0, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A4[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A4, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A8[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A8[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A8[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A8, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007AC[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007AC[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007AC[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007AC[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007AC[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007AC[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007AC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007AC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007AC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007AC, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007B0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007B0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007B0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007B0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007B0[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007B0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B0, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007B4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007B4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007B4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007B4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007B4[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007B4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B4, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007B8[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007B8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B8, 0x00003F01U ,0x00000200U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007BC[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. Speed = 0 + // .. ==> 0XF80007BC[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007BC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007BC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007BC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007BC, 0x00003F01U ,0x00000201U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007C0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007C0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 7 + // .. ==> 0XF80007C0[7:5] = 0x00000007U + // .. ==> MASK : 0x000000E0U VAL : 0x000000E0U + // .. Speed = 0 + // .. ==> 0XF80007C0[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C0, 0x00003FFFU ,0x000002E0U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007C4[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007C4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 7 + // .. ==> 0XF80007C4[7:5] = 0x00000007U + // .. ==> MASK : 0x000000E0U VAL : 0x000000E0U + // .. Speed = 0 + // .. ==> 0XF80007C4[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C4, 0x00003FFFU ,0x000002E1U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007C8[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007C8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C8[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF80007C8[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007C8[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C8, 0x00003FFFU ,0x00000201U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007CC[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007CC[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007CC[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007CC[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF80007CC[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007CC[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007CC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007CC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007CC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007CC, 0x00003FFFU ,0x00000201U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007D0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007D0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007D0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007D0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007D0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 0 + // .. ==> 0XF80007D0[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007D0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007D0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007D0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007D0, 0x00003FFFU ,0x00000280U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007D4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007D4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007D4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007D4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007D4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 0 + // .. ==> 0XF80007D4[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007D4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007D4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007D4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007D4, 0x00003FFFU ,0x00000280U), + // .. SDIO0_CD_SEL = 47 + // .. ==> 0XF8000830[21:16] = 0x0000002FU + // .. ==> MASK : 0x003F0000U VAL : 0x002F0000U + // .. + EMIT_MASKWRITE(0XF8000830, 0x003F0000U ,0x002F0000U), + // .. FINISH: MIO PROGRAMMING + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_peripherals_init_data_2_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: DDR TERM/IBUF_DISABLE_MODE SETTINGS + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B48[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B48[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B48, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B4C[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B4C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B4C, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B50[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B50[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B50, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B54[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B54[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B54, 0x00000180U ,0x00000180U), + // .. FINISH: DDR TERM/IBUF_DISABLE_MODE SETTINGS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // .. START: SRAM/NOR SET OPMODE + // .. FINISH: SRAM/NOR SET OPMODE + // .. START: UART REGISTERS + // .. BDIV = 0x5 + // .. ==> 0XE0001034[7:0] = 0x00000005U + // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. + EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000005U), + // .. CD = 0x9 + // .. ==> 0XE0001018[15:0] = 0x00000009U + // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + // .. + EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x00000009U), + // .. STPBRK = 0x0 + // .. ==> 0XE0001000[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. STTBRK = 0x0 + // .. ==> 0XE0001000[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. RSTTO = 0x0 + // .. ==> 0XE0001000[6:6] = 0x00000000U + // .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. TXDIS = 0x0 + // .. ==> 0XE0001000[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. TXEN = 0x1 + // .. ==> 0XE0001000[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. RXDIS = 0x0 + // .. ==> 0XE0001000[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. RXEN = 0x1 + // .. ==> 0XE0001000[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. TXRES = 0x1 + // .. ==> 0XE0001000[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. RXRES = 0x1 + // .. ==> 0XE0001000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XE0001000, 0x000001FFU ,0x00000017U), + // .. IRMODE = 0x0 + // .. ==> 0XE0001004[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. UCLKEN = 0x0 + // .. ==> 0XE0001004[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. CHMODE = 0x0 + // .. ==> 0XE0001004[9:8] = 0x00000000U + // .. ==> MASK : 0x00000300U VAL : 0x00000000U + // .. NBSTOP = 0x0 + // .. ==> 0XE0001004[7:6] = 0x00000000U + // .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. PAR = 0x4 + // .. ==> 0XE0001004[5:3] = 0x00000004U + // .. ==> MASK : 0x00000038U VAL : 0x00000020U + // .. CHRL = 0x0 + // .. ==> 0XE0001004[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. CLKS = 0x0 + // .. ==> 0XE0001004[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XE0001004, 0x00000FFFU ,0x00000020U), + // .. BDIV = 0x5 + // .. ==> 0XE0000034[7:0] = 0x00000005U + // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. + EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000005U), + // .. CD = 0x9 + // .. ==> 0XE0000018[15:0] = 0x00000009U + // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + // .. + EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x00000009U), + // .. STPBRK = 0x0 + // .. ==> 0XE0000000[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. STTBRK = 0x0 + // .. ==> 0XE0000000[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. RSTTO = 0x0 + // .. ==> 0XE0000000[6:6] = 0x00000000U + // .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. TXDIS = 0x0 + // .. ==> 0XE0000000[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. TXEN = 0x1 + // .. ==> 0XE0000000[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. RXDIS = 0x0 + // .. ==> 0XE0000000[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. RXEN = 0x1 + // .. ==> 0XE0000000[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. TXRES = 0x1 + // .. ==> 0XE0000000[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. RXRES = 0x1 + // .. ==> 0XE0000000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XE0000000, 0x000001FFU ,0x00000017U), + // .. IRMODE = 0x0 + // .. ==> 0XE0000004[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. UCLKEN = 0x0 + // .. ==> 0XE0000004[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. CHMODE = 0x0 + // .. ==> 0XE0000004[9:8] = 0x00000000U + // .. ==> MASK : 0x00000300U VAL : 0x00000000U + // .. NBSTOP = 0x0 + // .. ==> 0XE0000004[7:6] = 0x00000000U + // .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. PAR = 0x4 + // .. ==> 0XE0000004[5:3] = 0x00000004U + // .. ==> MASK : 0x00000038U VAL : 0x00000020U + // .. CHRL = 0x0 + // .. ==> 0XE0000004[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. CLKS = 0x0 + // .. ==> 0XE0000004[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XE0000004, 0x00000FFFU ,0x00000020U), + // .. FINISH: UART REGISTERS + // .. START: QSPI REGISTERS + // .. Holdb_dr = 1 + // .. ==> 0XE000D000[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XE000D000, 0x00080000U ,0x00080000U), + // .. FINISH: QSPI REGISTERS + // .. START: PL POWER ON RESET REGISTERS + // .. PCFG_POR_CNT_4K = 0 + // .. ==> 0XF8007000[29:29] = 0x00000000U + // .. ==> MASK : 0x20000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8007000, 0x20000000U ,0x00000000U), + // .. FINISH: PL POWER ON RESET REGISTERS + // .. START: SMC TIMING CALCULATION REGISTER UPDATE + // .. .. START: NAND SET CYCLE + // .. .. FINISH: NAND SET CYCLE + // .. .. START: OPMODE + // .. .. FINISH: OPMODE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: SRAM/NOR CS0 SET CYCLE + // .. .. FINISH: SRAM/NOR CS0 SET CYCLE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: NOR CS0 BASE ADDRESS + // .. .. FINISH: NOR CS0 BASE ADDRESS + // .. .. START: SRAM/NOR CS1 SET CYCLE + // .. .. FINISH: SRAM/NOR CS1 SET CYCLE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: NOR CS1 BASE ADDRESS + // .. .. FINISH: NOR CS1 BASE ADDRESS + // .. .. START: USB RESET + // .. .. .. START: DIR MODE BANK 0 + // .. .. .. FINISH: DIR MODE BANK 0 + // .. .. .. START: DIR MODE BANK 1 + // .. .. .. DIRECTION_1 = 0x4000 + // .. .. .. ==> 0XE000A244[21:0] = 0x00004000U + // .. .. .. ==> MASK : 0x003FFFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A244, 0x003FFFFFU ,0x00004000U), + // .. .. .. FINISH: DIR MODE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x4000 + // .. .. .. ==> 0XE000A008[15:0] = 0x00004000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF4000U), + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE BANK 0 + // .. .. .. FINISH: OUTPUT ENABLE BANK 0 + // .. .. .. START: OUTPUT ENABLE BANK 1 + // .. .. .. OP_ENABLE_1 = 0x4000 + // .. .. .. ==> 0XE000A248[21:0] = 0x00004000U + // .. .. .. ==> MASK : 0x003FFFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A248, 0x003FFFFFU ,0x00004000U), + // .. .. .. FINISH: OUTPUT ENABLE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x0 + // .. .. .. ==> 0XE000A008[15:0] = 0x00000000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF0000U), + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x4000 + // .. .. .. ==> 0XE000A008[15:0] = 0x00004000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF4000U), + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: USB RESET + // .. .. START: ENET RESET + // .. .. .. START: DIR MODE BANK 0 + // .. .. .. FINISH: DIR MODE BANK 0 + // .. .. .. START: DIR MODE BANK 1 + // .. .. .. FINISH: DIR MODE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE BANK 0 + // .. .. .. FINISH: OUTPUT ENABLE BANK 0 + // .. .. .. START: OUTPUT ENABLE BANK 1 + // .. .. .. FINISH: OUTPUT ENABLE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: ENET RESET + // .. .. START: I2C RESET + // .. .. .. START: DIR MODE GPIO BANK0 + // .. .. .. FINISH: DIR MODE GPIO BANK0 + // .. .. .. START: DIR MODE GPIO BANK1 + // .. .. .. FINISH: DIR MODE GPIO BANK1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE + // .. .. .. FINISH: OUTPUT ENABLE + // .. .. .. START: OUTPUT ENABLE + // .. .. .. FINISH: OUTPUT ENABLE + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: I2C RESET + // .. FINISH: SMC TIMING CALCULATION REGISTER UPDATE + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_post_config_2_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: ENABLING LEVEL SHIFTER + // .. USER_INP_ICT_EN_0 = 3 + // .. ==> 0XF8000900[1:0] = 0x00000003U + // .. ==> MASK : 0x00000003U VAL : 0x00000003U + // .. USER_INP_ICT_EN_1 = 3 + // .. ==> 0XF8000900[3:2] = 0x00000003U + // .. ==> MASK : 0x0000000CU VAL : 0x0000000CU + // .. + EMIT_MASKWRITE(0XF8000900, 0x0000000FU ,0x0000000FU), + // .. FINISH: ENABLING LEVEL SHIFTER + // .. START: FPGA RESETS TO 1 + // .. reserved_3 = 127 + // .. ==> 0XF8000240[31:25] = 0x0000007FU + // .. ==> MASK : 0xFE000000U VAL : 0xFE000000U + // .. FPGA_ACP_RST = 1 + // .. ==> 0XF8000240[24:24] = 0x00000001U + // .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. FPGA_AXDS3_RST = 1 + // .. ==> 0XF8000240[23:23] = 0x00000001U + // .. ==> MASK : 0x00800000U VAL : 0x00800000U + // .. FPGA_AXDS2_RST = 1 + // .. ==> 0XF8000240[22:22] = 0x00000001U + // .. ==> MASK : 0x00400000U VAL : 0x00400000U + // .. FPGA_AXDS1_RST = 1 + // .. ==> 0XF8000240[21:21] = 0x00000001U + // .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. FPGA_AXDS0_RST = 1 + // .. ==> 0XF8000240[20:20] = 0x00000001U + // .. ==> MASK : 0x00100000U VAL : 0x00100000U + // .. reserved_2 = 3 + // .. ==> 0XF8000240[19:18] = 0x00000003U + // .. ==> MASK : 0x000C0000U VAL : 0x000C0000U + // .. FSSW1_FPGA_RST = 1 + // .. ==> 0XF8000240[17:17] = 0x00000001U + // .. ==> MASK : 0x00020000U VAL : 0x00020000U + // .. FSSW0_FPGA_RST = 1 + // .. ==> 0XF8000240[16:16] = 0x00000001U + // .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. reserved_1 = 15 + // .. ==> 0XF8000240[15:14] = 0x0000000FU + // .. ==> MASK : 0x0000C000U VAL : 0x0000C000U + // .. FPGA_FMSW1_RST = 1 + // .. ==> 0XF8000240[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. FPGA_FMSW0_RST = 1 + // .. ==> 0XF8000240[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. FPGA_DMA3_RST = 1 + // .. ==> 0XF8000240[11:11] = 0x00000001U + // .. ==> MASK : 0x00000800U VAL : 0x00000800U + // .. FPGA_DMA2_RST = 1 + // .. ==> 0XF8000240[10:10] = 0x00000001U + // .. ==> MASK : 0x00000400U VAL : 0x00000400U + // .. FPGA_DMA1_RST = 1 + // .. ==> 0XF8000240[9:9] = 0x00000001U + // .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. FPGA_DMA0_RST = 1 + // .. ==> 0XF8000240[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. reserved = 15 + // .. ==> 0XF8000240[7:4] = 0x0000000FU + // .. ==> MASK : 0x000000F0U VAL : 0x000000F0U + // .. FPGA3_OUT_RST = 1 + // .. ==> 0XF8000240[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. FPGA2_OUT_RST = 1 + // .. ==> 0XF8000240[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. FPGA1_OUT_RST = 1 + // .. ==> 0XF8000240[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. FPGA0_OUT_RST = 1 + // .. ==> 0XF8000240[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XF8000240, 0xFFFFFFFFU ,0xFFFFFFFFU), + // .. FINISH: FPGA RESETS TO 1 + // .. START: FPGA RESETS TO 0 + // .. reserved_3 = 0 + // .. ==> 0XF8000240[31:25] = 0x00000000U + // .. ==> MASK : 0xFE000000U VAL : 0x00000000U + // .. FPGA_ACP_RST = 0 + // .. ==> 0XF8000240[24:24] = 0x00000000U + // .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. FPGA_AXDS3_RST = 0 + // .. ==> 0XF8000240[23:23] = 0x00000000U + // .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. FPGA_AXDS2_RST = 0 + // .. ==> 0XF8000240[22:22] = 0x00000000U + // .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. FPGA_AXDS1_RST = 0 + // .. ==> 0XF8000240[21:21] = 0x00000000U + // .. ==> MASK : 0x00200000U VAL : 0x00000000U + // .. FPGA_AXDS0_RST = 0 + // .. ==> 0XF8000240[20:20] = 0x00000000U + // .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. reserved_2 = 0 + // .. ==> 0XF8000240[19:18] = 0x00000000U + // .. ==> MASK : 0x000C0000U VAL : 0x00000000U + // .. FSSW1_FPGA_RST = 0 + // .. ==> 0XF8000240[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. FSSW0_FPGA_RST = 0 + // .. ==> 0XF8000240[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reserved_1 = 0 + // .. ==> 0XF8000240[15:14] = 0x00000000U + // .. ==> MASK : 0x0000C000U VAL : 0x00000000U + // .. FPGA_FMSW1_RST = 0 + // .. ==> 0XF8000240[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. FPGA_FMSW0_RST = 0 + // .. ==> 0XF8000240[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. FPGA_DMA3_RST = 0 + // .. ==> 0XF8000240[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. FPGA_DMA2_RST = 0 + // .. ==> 0XF8000240[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. FPGA_DMA1_RST = 0 + // .. ==> 0XF8000240[9:9] = 0x00000000U + // .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. FPGA_DMA0_RST = 0 + // .. ==> 0XF8000240[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. reserved = 0 + // .. ==> 0XF8000240[7:4] = 0x00000000U + // .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. FPGA3_OUT_RST = 0 + // .. ==> 0XF8000240[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. FPGA2_OUT_RST = 0 + // .. ==> 0XF8000240[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. FPGA1_OUT_RST = 0 + // .. ==> 0XF8000240[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. FPGA0_OUT_RST = 0 + // .. ==> 0XF8000240[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000240, 0xFFFFFFFFU ,0x00000000U), + // .. FINISH: FPGA RESETS TO 0 + // .. START: AFI REGISTERS + // .. .. START: AFI0 REGISTERS + // .. .. FINISH: AFI0 REGISTERS + // .. .. START: AFI1 REGISTERS + // .. .. FINISH: AFI1 REGISTERS + // .. .. START: AFI2 REGISTERS + // .. .. FINISH: AFI2 REGISTERS + // .. .. START: AFI3 REGISTERS + // .. .. FINISH: AFI3 REGISTERS + // .. FINISH: AFI REGISTERS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_pll_init_data_3_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: PLL SLCR REGISTERS + // .. .. START: ARM PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000110[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000110[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x177 + // .. .. ==> 0XF8000110[21:12] = 0x00000177U + // .. .. ==> MASK : 0x003FF000U VAL : 0x00177000U + // .. .. + EMIT_MASKWRITE(0XF8000110, 0x003FFFF0U ,0x001772C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x1a + // .. .. .. ==> 0XF8000100[18:12] = 0x0000001AU + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x0001A000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x0007F000U ,0x0001A000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000100[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000100[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000100[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. ARM_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000001U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000100[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000100, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. .. SRCSEL = 0x0 + // .. .. .. ==> 0XF8000120[5:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. .. .. DIVISOR = 0x2 + // .. .. .. ==> 0XF8000120[13:8] = 0x00000002U + // .. .. .. ==> MASK : 0x00003F00U VAL : 0x00000200U + // .. .. .. CPU_6OR4XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[24:24] = 0x00000001U + // .. .. .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. .. .. CPU_3OR2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[25:25] = 0x00000001U + // .. .. .. ==> MASK : 0x02000000U VAL : 0x02000000U + // .. .. .. CPU_2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[26:26] = 0x00000001U + // .. .. .. ==> MASK : 0x04000000U VAL : 0x04000000U + // .. .. .. CPU_1XCLKACT = 0x1 + // .. .. .. ==> 0XF8000120[27:27] = 0x00000001U + // .. .. .. ==> MASK : 0x08000000U VAL : 0x08000000U + // .. .. .. CPU_PERI_CLKACT = 0x1 + // .. .. .. ==> 0XF8000120[28:28] = 0x00000001U + // .. .. .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000120, 0x1F003F30U ,0x1F000200U), + // .. .. FINISH: ARM PLL INIT + // .. .. START: DDR PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000114[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000114[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x1db + // .. .. ==> 0XF8000114[21:12] = 0x000001DBU + // .. .. ==> MASK : 0x003FF000U VAL : 0x001DB000U + // .. .. + EMIT_MASKWRITE(0XF8000114, 0x003FFFF0U ,0x001DB2C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x15 + // .. .. .. ==> 0XF8000104[18:12] = 0x00000015U + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x00015000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x0007F000U ,0x00015000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000104[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000104[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000104[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. DDR_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[1:1] = 0x00000001U + // .. .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000002U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000104[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000104, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. .. DDR_3XCLKACT = 0x1 + // .. .. .. ==> 0XF8000124[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. DDR_2XCLKACT = 0x1 + // .. .. .. ==> 0XF8000124[1:1] = 0x00000001U + // .. .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. .. DDR_3XCLK_DIVISOR = 0x2 + // .. .. .. ==> 0XF8000124[25:20] = 0x00000002U + // .. .. .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. .. .. DDR_2XCLK_DIVISOR = 0x3 + // .. .. .. ==> 0XF8000124[31:26] = 0x00000003U + // .. .. .. ==> MASK : 0xFC000000U VAL : 0x0C000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000124, 0xFFF00003U ,0x0C200003U), + // .. .. FINISH: DDR PLL INIT + // .. .. START: IO PLL INIT + // .. .. PLL_RES = 0xc + // .. .. ==> 0XF8000118[7:4] = 0x0000000CU + // .. .. ==> MASK : 0x000000F0U VAL : 0x000000C0U + // .. .. PLL_CP = 0x2 + // .. .. ==> 0XF8000118[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. LOCK_CNT = 0x1f4 + // .. .. ==> 0XF8000118[21:12] = 0x000001F4U + // .. .. ==> MASK : 0x003FF000U VAL : 0x001F4000U + // .. .. + EMIT_MASKWRITE(0XF8000118, 0x003FFFF0U ,0x001F42C0U), + // .. .. .. START: UPDATE FB_DIV + // .. .. .. PLL_FDIV = 0x14 + // .. .. .. ==> 0XF8000108[18:12] = 0x00000014U + // .. .. .. ==> MASK : 0x0007F000U VAL : 0x00014000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x0007F000U ,0x00014000U), + // .. .. .. FINISH: UPDATE FB_DIV + // .. .. .. START: BY PASS PLL + // .. .. .. PLL_BYPASS_FORCE = 1 + // .. .. .. ==> 0XF8000108[4:4] = 0x00000001U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000010U ,0x00000010U), + // .. .. .. FINISH: BY PASS PLL + // .. .. .. START: ASSERT RESET + // .. .. .. PLL_RESET = 1 + // .. .. .. ==> 0XF8000108[0:0] = 0x00000001U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000001U ,0x00000001U), + // .. .. .. FINISH: ASSERT RESET + // .. .. .. START: DEASSERT RESET + // .. .. .. PLL_RESET = 0 + // .. .. .. ==> 0XF8000108[0:0] = 0x00000000U + // .. .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000001U ,0x00000000U), + // .. .. .. FINISH: DEASSERT RESET + // .. .. .. START: CHECK PLL STATUS + // .. .. .. IO_PLL_LOCK = 1 + // .. .. .. ==> 0XF800010C[2:2] = 0x00000001U + // .. .. .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. .. .. + EMIT_MASKPOLL(0XF800010C, 0x00000004U), + // .. .. .. FINISH: CHECK PLL STATUS + // .. .. .. START: REMOVE PLL BY PASS + // .. .. .. PLL_BYPASS_FORCE = 0 + // .. .. .. ==> 0XF8000108[4:4] = 0x00000000U + // .. .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XF8000108, 0x00000010U ,0x00000000U), + // .. .. .. FINISH: REMOVE PLL BY PASS + // .. .. FINISH: IO PLL INIT + // .. FINISH: PLL SLCR REGISTERS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_clock_init_data_3_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: CLOCK CONTROL SLCR REGISTERS + // .. CLKACT = 0x1 + // .. ==> 0XF8000128[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. DIVISOR0 = 0x34 + // .. ==> 0XF8000128[13:8] = 0x00000034U + // .. ==> MASK : 0x00003F00U VAL : 0x00003400U + // .. DIVISOR1 = 0x2 + // .. ==> 0XF8000128[25:20] = 0x00000002U + // .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. + EMIT_MASKWRITE(0XF8000128, 0x03F03F01U ,0x00203401U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000138[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000138[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000138, 0x00000011U ,0x00000001U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000140[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000140[6:4] = 0x00000000U + // .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. DIVISOR = 0x8 + // .. ==> 0XF8000140[13:8] = 0x00000008U + // .. ==> MASK : 0x00003F00U VAL : 0x00000800U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000140[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000140, 0x03F03F71U ,0x00100801U), + // .. CLKACT = 0x1 + // .. ==> 0XF800014C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF800014C[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x5 + // .. ==> 0XF800014C[13:8] = 0x00000005U + // .. ==> MASK : 0x00003F00U VAL : 0x00000500U + // .. + EMIT_MASKWRITE(0XF800014C, 0x00003F31U ,0x00000501U), + // .. CLKACT0 = 0x1 + // .. ==> 0XF8000150[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. CLKACT1 = 0x0 + // .. ==> 0XF8000150[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000150[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x14 + // .. ==> 0XF8000150[13:8] = 0x00000014U + // .. ==> MASK : 0x00003F00U VAL : 0x00001400U + // .. + EMIT_MASKWRITE(0XF8000150, 0x00003F33U ,0x00001401U), + // .. CLKACT0 = 0x1 + // .. ==> 0XF8000154[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. CLKACT1 = 0x1 + // .. ==> 0XF8000154[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000154[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x14 + // .. ==> 0XF8000154[13:8] = 0x00000014U + // .. ==> MASK : 0x00003F00U VAL : 0x00001400U + // .. + EMIT_MASKWRITE(0XF8000154, 0x00003F33U ,0x00001403U), + // .. CLKACT = 0x1 + // .. ==> 0XF8000168[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. SRCSEL = 0x0 + // .. ==> 0XF8000168[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR = 0x5 + // .. ==> 0XF8000168[13:8] = 0x00000005U + // .. ==> MASK : 0x00003F00U VAL : 0x00000500U + // .. + EMIT_MASKWRITE(0XF8000168, 0x00003F31U ,0x00000501U), + // .. SRCSEL = 0x0 + // .. ==> 0XF8000170[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR0 = 0xa + // .. ==> 0XF8000170[13:8] = 0x0000000AU + // .. ==> MASK : 0x00003F00U VAL : 0x00000A00U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000170[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000170, 0x03F03F30U ,0x00100A00U), + // .. SRCSEL = 0x3 + // .. ==> 0XF8000180[5:4] = 0x00000003U + // .. ==> MASK : 0x00000030U VAL : 0x00000030U + // .. DIVISOR0 = 0x6 + // .. ==> 0XF8000180[13:8] = 0x00000006U + // .. ==> MASK : 0x00003F00U VAL : 0x00000600U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF8000180[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF8000180, 0x03F03F30U ,0x00100630U), + // .. SRCSEL = 0x2 + // .. ==> 0XF8000190[5:4] = 0x00000002U + // .. ==> MASK : 0x00000030U VAL : 0x00000020U + // .. DIVISOR0 = 0x35 + // .. ==> 0XF8000190[13:8] = 0x00000035U + // .. ==> MASK : 0x00003F00U VAL : 0x00003500U + // .. DIVISOR1 = 0x2 + // .. ==> 0XF8000190[25:20] = 0x00000002U + // .. ==> MASK : 0x03F00000U VAL : 0x00200000U + // .. + EMIT_MASKWRITE(0XF8000190, 0x03F03F30U ,0x00203520U), + // .. SRCSEL = 0x0 + // .. ==> 0XF80001A0[5:4] = 0x00000000U + // .. ==> MASK : 0x00000030U VAL : 0x00000000U + // .. DIVISOR0 = 0xa + // .. ==> 0XF80001A0[13:8] = 0x0000000AU + // .. ==> MASK : 0x00003F00U VAL : 0x00000A00U + // .. DIVISOR1 = 0x1 + // .. ==> 0XF80001A0[25:20] = 0x00000001U + // .. ==> MASK : 0x03F00000U VAL : 0x00100000U + // .. + EMIT_MASKWRITE(0XF80001A0, 0x03F03F30U ,0x00100A00U), + // .. CLK_621_TRUE = 0x1 + // .. ==> 0XF80001C4[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XF80001C4, 0x00000001U ,0x00000001U), + // .. DMA_CPU_2XCLKACT = 0x1 + // .. ==> 0XF800012C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. USB0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. USB1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. GEM0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[6:6] = 0x00000001U + // .. ==> MASK : 0x00000040U VAL : 0x00000040U + // .. GEM1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. SDI0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[10:10] = 0x00000001U + // .. ==> MASK : 0x00000400U VAL : 0x00000400U + // .. SDI1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. SPI0_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[14:14] = 0x00000000U + // .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. SPI1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[15:15] = 0x00000000U + // .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. CAN0_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. CAN1_CPU_1XCLKACT = 0x0 + // .. ==> 0XF800012C[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. I2C0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[18:18] = 0x00000001U + // .. ==> MASK : 0x00040000U VAL : 0x00040000U + // .. I2C1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. UART0_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[20:20] = 0x00000001U + // .. ==> MASK : 0x00100000U VAL : 0x00100000U + // .. UART1_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[21:21] = 0x00000001U + // .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. GPIO_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[22:22] = 0x00000001U + // .. ==> MASK : 0x00400000U VAL : 0x00400000U + // .. LQSPI_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[23:23] = 0x00000001U + // .. ==> MASK : 0x00800000U VAL : 0x00800000U + // .. SMC_CPU_1XCLKACT = 0x1 + // .. ==> 0XF800012C[24:24] = 0x00000001U + // .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. + EMIT_MASKWRITE(0XF800012C, 0x01FFCCCDU ,0x01FC044DU), + // .. FINISH: CLOCK CONTROL SLCR REGISTERS + // .. START: THIS SHOULD BE BLANK + // .. FINISH: THIS SHOULD BE BLANK + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_ddr_init_data_3_0[] = { + // START: top + // .. START: DDR INITIALIZATION + // .. .. START: LOCK DDR + // .. .. reg_ddrc_soft_rstb = 0 + // .. .. ==> 0XF8006000[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_powerdown_en = 0x0 + // .. .. ==> 0XF8006000[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_ddrc_data_bus_width = 0x0 + // .. .. ==> 0XF8006000[3:2] = 0x00000000U + // .. .. ==> MASK : 0x0000000CU VAL : 0x00000000U + // .. .. reg_ddrc_burst8_refresh = 0x0 + // .. .. ==> 0XF8006000[6:4] = 0x00000000U + // .. .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. .. reg_ddrc_rdwr_idle_gap = 0x1 + // .. .. ==> 0XF8006000[13:7] = 0x00000001U + // .. .. ==> MASK : 0x00003F80U VAL : 0x00000080U + // .. .. reg_ddrc_dis_rd_bypass = 0x0 + // .. .. ==> 0XF8006000[14:14] = 0x00000000U + // .. .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_act_bypass = 0x0 + // .. .. ==> 0XF8006000[15:15] = 0x00000000U + // .. .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_auto_refresh = 0x0 + // .. .. ==> 0XF8006000[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006000, 0x0001FFFFU ,0x00000080U), + // .. .. FINISH: LOCK DDR + // .. .. reg_ddrc_t_rfc_nom_x32 = 0x7f + // .. .. ==> 0XF8006004[11:0] = 0x0000007FU + // .. .. ==> MASK : 0x00000FFFU VAL : 0x0000007FU + // .. .. reserved_reg_ddrc_active_ranks = 0x1 + // .. .. ==> 0XF8006004[13:12] = 0x00000001U + // .. .. ==> MASK : 0x00003000U VAL : 0x00001000U + // .. .. reg_ddrc_addrmap_cs_bit0 = 0x0 + // .. .. ==> 0XF8006004[18:14] = 0x00000000U + // .. .. ==> MASK : 0x0007C000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006004, 0x0007FFFFU ,0x0000107FU), + // .. .. reg_ddrc_hpr_min_non_critical_x32 = 0xf + // .. .. ==> 0XF8006008[10:0] = 0x0000000FU + // .. .. ==> MASK : 0x000007FFU VAL : 0x0000000FU + // .. .. reg_ddrc_hpr_max_starve_x32 = 0xf + // .. .. ==> 0XF8006008[21:11] = 0x0000000FU + // .. .. ==> MASK : 0x003FF800U VAL : 0x00007800U + // .. .. reg_ddrc_hpr_xact_run_length = 0xf + // .. .. ==> 0XF8006008[25:22] = 0x0000000FU + // .. .. ==> MASK : 0x03C00000U VAL : 0x03C00000U + // .. .. + EMIT_MASKWRITE(0XF8006008, 0x03FFFFFFU ,0x03C0780FU), + // .. .. reg_ddrc_lpr_min_non_critical_x32 = 0x1 + // .. .. ==> 0XF800600C[10:0] = 0x00000001U + // .. .. ==> MASK : 0x000007FFU VAL : 0x00000001U + // .. .. reg_ddrc_lpr_max_starve_x32 = 0x2 + // .. .. ==> 0XF800600C[21:11] = 0x00000002U + // .. .. ==> MASK : 0x003FF800U VAL : 0x00001000U + // .. .. reg_ddrc_lpr_xact_run_length = 0x8 + // .. .. ==> 0XF800600C[25:22] = 0x00000008U + // .. .. ==> MASK : 0x03C00000U VAL : 0x02000000U + // .. .. + EMIT_MASKWRITE(0XF800600C, 0x03FFFFFFU ,0x02001001U), + // .. .. reg_ddrc_w_min_non_critical_x32 = 0x1 + // .. .. ==> 0XF8006010[10:0] = 0x00000001U + // .. .. ==> MASK : 0x000007FFU VAL : 0x00000001U + // .. .. reg_ddrc_w_xact_run_length = 0x8 + // .. .. ==> 0XF8006010[14:11] = 0x00000008U + // .. .. ==> MASK : 0x00007800U VAL : 0x00004000U + // .. .. reg_ddrc_w_max_starve_x32 = 0x2 + // .. .. ==> 0XF8006010[25:15] = 0x00000002U + // .. .. ==> MASK : 0x03FF8000U VAL : 0x00010000U + // .. .. + EMIT_MASKWRITE(0XF8006010, 0x03FFFFFFU ,0x00014001U), + // .. .. reg_ddrc_t_rc = 0x1a + // .. .. ==> 0XF8006014[5:0] = 0x0000001AU + // .. .. ==> MASK : 0x0000003FU VAL : 0x0000001AU + // .. .. reg_ddrc_t_rfc_min = 0x54 + // .. .. ==> 0XF8006014[13:6] = 0x00000054U + // .. .. ==> MASK : 0x00003FC0U VAL : 0x00001500U + // .. .. reg_ddrc_post_selfref_gap_x32 = 0x10 + // .. .. ==> 0XF8006014[20:14] = 0x00000010U + // .. .. ==> MASK : 0x001FC000U VAL : 0x00040000U + // .. .. + EMIT_MASKWRITE(0XF8006014, 0x001FFFFFU ,0x0004151AU), + // .. .. reg_ddrc_wr2pre = 0x12 + // .. .. ==> 0XF8006018[4:0] = 0x00000012U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000012U + // .. .. reg_ddrc_powerdown_to_x32 = 0x6 + // .. .. ==> 0XF8006018[9:5] = 0x00000006U + // .. .. ==> MASK : 0x000003E0U VAL : 0x000000C0U + // .. .. reg_ddrc_t_faw = 0x15 + // .. .. ==> 0XF8006018[15:10] = 0x00000015U + // .. .. ==> MASK : 0x0000FC00U VAL : 0x00005400U + // .. .. reg_ddrc_t_ras_max = 0x23 + // .. .. ==> 0XF8006018[21:16] = 0x00000023U + // .. .. ==> MASK : 0x003F0000U VAL : 0x00230000U + // .. .. reg_ddrc_t_ras_min = 0x13 + // .. .. ==> 0XF8006018[26:22] = 0x00000013U + // .. .. ==> MASK : 0x07C00000U VAL : 0x04C00000U + // .. .. reg_ddrc_t_cke = 0x4 + // .. .. ==> 0XF8006018[31:28] = 0x00000004U + // .. .. ==> MASK : 0xF0000000U VAL : 0x40000000U + // .. .. + EMIT_MASKWRITE(0XF8006018, 0xF7FFFFFFU ,0x44E354D2U), + // .. .. reg_ddrc_write_latency = 0x5 + // .. .. ==> 0XF800601C[4:0] = 0x00000005U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000005U + // .. .. reg_ddrc_rd2wr = 0x7 + // .. .. ==> 0XF800601C[9:5] = 0x00000007U + // .. .. ==> MASK : 0x000003E0U VAL : 0x000000E0U + // .. .. reg_ddrc_wr2rd = 0xe + // .. .. ==> 0XF800601C[14:10] = 0x0000000EU + // .. .. ==> MASK : 0x00007C00U VAL : 0x00003800U + // .. .. reg_ddrc_t_xp = 0x4 + // .. .. ==> 0XF800601C[19:15] = 0x00000004U + // .. .. ==> MASK : 0x000F8000U VAL : 0x00020000U + // .. .. reg_ddrc_pad_pd = 0x0 + // .. .. ==> 0XF800601C[22:20] = 0x00000000U + // .. .. ==> MASK : 0x00700000U VAL : 0x00000000U + // .. .. reg_ddrc_rd2pre = 0x4 + // .. .. ==> 0XF800601C[27:23] = 0x00000004U + // .. .. ==> MASK : 0x0F800000U VAL : 0x02000000U + // .. .. reg_ddrc_t_rcd = 0x7 + // .. .. ==> 0XF800601C[31:28] = 0x00000007U + // .. .. ==> MASK : 0xF0000000U VAL : 0x70000000U + // .. .. + EMIT_MASKWRITE(0XF800601C, 0xFFFFFFFFU ,0x720238E5U), + // .. .. reg_ddrc_t_ccd = 0x4 + // .. .. ==> 0XF8006020[4:2] = 0x00000004U + // .. .. ==> MASK : 0x0000001CU VAL : 0x00000010U + // .. .. reg_ddrc_t_rrd = 0x6 + // .. .. ==> 0XF8006020[7:5] = 0x00000006U + // .. .. ==> MASK : 0x000000E0U VAL : 0x000000C0U + // .. .. reg_ddrc_refresh_margin = 0x2 + // .. .. ==> 0XF8006020[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. reg_ddrc_t_rp = 0x7 + // .. .. ==> 0XF8006020[15:12] = 0x00000007U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00007000U + // .. .. reg_ddrc_refresh_to_x32 = 0x8 + // .. .. ==> 0XF8006020[20:16] = 0x00000008U + // .. .. ==> MASK : 0x001F0000U VAL : 0x00080000U + // .. .. reg_ddrc_mobile = 0x0 + // .. .. ==> 0XF8006020[22:22] = 0x00000000U + // .. .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. .. reg_ddrc_en_dfi_dram_clk_disable = 0x0 + // .. .. ==> 0XF8006020[23:23] = 0x00000000U + // .. .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. .. reg_ddrc_read_latency = 0x7 + // .. .. ==> 0XF8006020[28:24] = 0x00000007U + // .. .. ==> MASK : 0x1F000000U VAL : 0x07000000U + // .. .. reg_phy_mode_ddr1_ddr2 = 0x1 + // .. .. ==> 0XF8006020[29:29] = 0x00000001U + // .. .. ==> MASK : 0x20000000U VAL : 0x20000000U + // .. .. reg_ddrc_dis_pad_pd = 0x0 + // .. .. ==> 0XF8006020[30:30] = 0x00000000U + // .. .. ==> MASK : 0x40000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006020, 0x7FDFFFFCU ,0x270872D0U), + // .. .. reg_ddrc_en_2t_timing_mode = 0x0 + // .. .. ==> 0XF8006024[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_prefer_write = 0x0 + // .. .. ==> 0XF8006024[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_ddrc_mr_wr = 0x0 + // .. .. ==> 0XF8006024[6:6] = 0x00000000U + // .. .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. .. reg_ddrc_mr_addr = 0x0 + // .. .. ==> 0XF8006024[8:7] = 0x00000000U + // .. .. ==> MASK : 0x00000180U VAL : 0x00000000U + // .. .. reg_ddrc_mr_data = 0x0 + // .. .. ==> 0XF8006024[24:9] = 0x00000000U + // .. .. ==> MASK : 0x01FFFE00U VAL : 0x00000000U + // .. .. ddrc_reg_mr_wr_busy = 0x0 + // .. .. ==> 0XF8006024[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. reg_ddrc_mr_type = 0x0 + // .. .. ==> 0XF8006024[26:26] = 0x00000000U + // .. .. ==> MASK : 0x04000000U VAL : 0x00000000U + // .. .. reg_ddrc_mr_rdata_valid = 0x0 + // .. .. ==> 0XF8006024[27:27] = 0x00000000U + // .. .. ==> MASK : 0x08000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006024, 0x0FFFFFC3U ,0x00000000U), + // .. .. reg_ddrc_final_wait_x32 = 0x7 + // .. .. ==> 0XF8006028[6:0] = 0x00000007U + // .. .. ==> MASK : 0x0000007FU VAL : 0x00000007U + // .. .. reg_ddrc_pre_ocd_x32 = 0x0 + // .. .. ==> 0XF8006028[10:7] = 0x00000000U + // .. .. ==> MASK : 0x00000780U VAL : 0x00000000U + // .. .. reg_ddrc_t_mrd = 0x4 + // .. .. ==> 0XF8006028[13:11] = 0x00000004U + // .. .. ==> MASK : 0x00003800U VAL : 0x00002000U + // .. .. + EMIT_MASKWRITE(0XF8006028, 0x00003FFFU ,0x00002007U), + // .. .. reg_ddrc_emr2 = 0x8 + // .. .. ==> 0XF800602C[15:0] = 0x00000008U + // .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000008U + // .. .. reg_ddrc_emr3 = 0x0 + // .. .. ==> 0XF800602C[31:16] = 0x00000000U + // .. .. ==> MASK : 0xFFFF0000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800602C, 0xFFFFFFFFU ,0x00000008U), + // .. .. reg_ddrc_mr = 0x930 + // .. .. ==> 0XF8006030[15:0] = 0x00000930U + // .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000930U + // .. .. reg_ddrc_emr = 0x4 + // .. .. ==> 0XF8006030[31:16] = 0x00000004U + // .. .. ==> MASK : 0xFFFF0000U VAL : 0x00040000U + // .. .. + EMIT_MASKWRITE(0XF8006030, 0xFFFFFFFFU ,0x00040930U), + // .. .. reg_ddrc_burst_rdwr = 0x4 + // .. .. ==> 0XF8006034[3:0] = 0x00000004U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000004U + // .. .. reg_ddrc_pre_cke_x1024 = 0x101 + // .. .. ==> 0XF8006034[13:4] = 0x00000101U + // .. .. ==> MASK : 0x00003FF0U VAL : 0x00001010U + // .. .. reg_ddrc_post_cke_x1024 = 0x1 + // .. .. ==> 0XF8006034[25:16] = 0x00000001U + // .. .. ==> MASK : 0x03FF0000U VAL : 0x00010000U + // .. .. reg_ddrc_burstchop = 0x0 + // .. .. ==> 0XF8006034[28:28] = 0x00000000U + // .. .. ==> MASK : 0x10000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006034, 0x13FF3FFFU ,0x00011014U), + // .. .. reg_ddrc_force_low_pri_n = 0x0 + // .. .. ==> 0XF8006038[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_dis_dq = 0x0 + // .. .. ==> 0XF8006038[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006038, 0x00000003U ,0x00000000U), + // .. .. reg_ddrc_addrmap_bank_b0 = 0x7 + // .. .. ==> 0XF800603C[3:0] = 0x00000007U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000007U + // .. .. reg_ddrc_addrmap_bank_b1 = 0x7 + // .. .. ==> 0XF800603C[7:4] = 0x00000007U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000070U + // .. .. reg_ddrc_addrmap_bank_b2 = 0x7 + // .. .. ==> 0XF800603C[11:8] = 0x00000007U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000700U + // .. .. reg_ddrc_addrmap_col_b5 = 0x0 + // .. .. ==> 0XF800603C[15:12] = 0x00000000U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b6 = 0x0 + // .. .. ==> 0XF800603C[19:16] = 0x00000000U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800603C, 0x000FFFFFU ,0x00000777U), + // .. .. reg_ddrc_addrmap_col_b2 = 0x0 + // .. .. ==> 0XF8006040[3:0] = 0x00000000U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b3 = 0x0 + // .. .. ==> 0XF8006040[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b4 = 0x0 + // .. .. ==> 0XF8006040[11:8] = 0x00000000U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b7 = 0x0 + // .. .. ==> 0XF8006040[15:12] = 0x00000000U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b8 = 0x0 + // .. .. ==> 0XF8006040[19:16] = 0x00000000U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00000000U + // .. .. reg_ddrc_addrmap_col_b9 = 0xf + // .. .. ==> 0XF8006040[23:20] = 0x0000000FU + // .. .. ==> MASK : 0x00F00000U VAL : 0x00F00000U + // .. .. reg_ddrc_addrmap_col_b10 = 0xf + // .. .. ==> 0XF8006040[27:24] = 0x0000000FU + // .. .. ==> MASK : 0x0F000000U VAL : 0x0F000000U + // .. .. reg_ddrc_addrmap_col_b11 = 0xf + // .. .. ==> 0XF8006040[31:28] = 0x0000000FU + // .. .. ==> MASK : 0xF0000000U VAL : 0xF0000000U + // .. .. + EMIT_MASKWRITE(0XF8006040, 0xFFFFFFFFU ,0xFFF00000U), + // .. .. reg_ddrc_addrmap_row_b0 = 0x6 + // .. .. ==> 0XF8006044[3:0] = 0x00000006U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000006U + // .. .. reg_ddrc_addrmap_row_b1 = 0x6 + // .. .. ==> 0XF8006044[7:4] = 0x00000006U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000060U + // .. .. reg_ddrc_addrmap_row_b2_11 = 0x6 + // .. .. ==> 0XF8006044[11:8] = 0x00000006U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000600U + // .. .. reg_ddrc_addrmap_row_b12 = 0x6 + // .. .. ==> 0XF8006044[15:12] = 0x00000006U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00006000U + // .. .. reg_ddrc_addrmap_row_b13 = 0x6 + // .. .. ==> 0XF8006044[19:16] = 0x00000006U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00060000U + // .. .. reg_ddrc_addrmap_row_b14 = 0xf + // .. .. ==> 0XF8006044[23:20] = 0x0000000FU + // .. .. ==> MASK : 0x00F00000U VAL : 0x00F00000U + // .. .. reg_ddrc_addrmap_row_b15 = 0xf + // .. .. ==> 0XF8006044[27:24] = 0x0000000FU + // .. .. ==> MASK : 0x0F000000U VAL : 0x0F000000U + // .. .. + EMIT_MASKWRITE(0XF8006044, 0x0FFFFFFFU ,0x0FF66666U), + // .. .. reg_phy_rd_local_odt = 0x0 + // .. .. ==> 0XF8006048[13:12] = 0x00000000U + // .. .. ==> MASK : 0x00003000U VAL : 0x00000000U + // .. .. reg_phy_wr_local_odt = 0x3 + // .. .. ==> 0XF8006048[15:14] = 0x00000003U + // .. .. ==> MASK : 0x0000C000U VAL : 0x0000C000U + // .. .. reg_phy_idle_local_odt = 0x3 + // .. .. ==> 0XF8006048[17:16] = 0x00000003U + // .. .. ==> MASK : 0x00030000U VAL : 0x00030000U + // .. .. + EMIT_MASKWRITE(0XF8006048, 0x0003F000U ,0x0003C000U), + // .. .. reg_phy_rd_cmd_to_data = 0x0 + // .. .. ==> 0XF8006050[3:0] = 0x00000000U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. .. reg_phy_wr_cmd_to_data = 0x0 + // .. .. ==> 0XF8006050[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_phy_rdc_we_to_re_delay = 0x8 + // .. .. ==> 0XF8006050[11:8] = 0x00000008U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000800U + // .. .. reg_phy_rdc_fifo_rst_disable = 0x0 + // .. .. ==> 0XF8006050[15:15] = 0x00000000U + // .. .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. .. reg_phy_use_fixed_re = 0x1 + // .. .. ==> 0XF8006050[16:16] = 0x00000001U + // .. .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. .. reg_phy_rdc_fifo_rst_err_cnt_clr = 0x0 + // .. .. ==> 0XF8006050[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_phy_dis_phy_ctrl_rstn = 0x0 + // .. .. ==> 0XF8006050[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. reg_phy_clk_stall_level = 0x0 + // .. .. ==> 0XF8006050[19:19] = 0x00000000U + // .. .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. .. reg_phy_gatelvl_num_of_dq0 = 0x7 + // .. .. ==> 0XF8006050[27:24] = 0x00000007U + // .. .. ==> MASK : 0x0F000000U VAL : 0x07000000U + // .. .. reg_phy_wrlvl_num_of_dq0 = 0x7 + // .. .. ==> 0XF8006050[31:28] = 0x00000007U + // .. .. ==> MASK : 0xF0000000U VAL : 0x70000000U + // .. .. + EMIT_MASKWRITE(0XF8006050, 0xFF0F8FFFU ,0x77010800U), + // .. .. reg_ddrc_dis_dll_calib = 0x0 + // .. .. ==> 0XF8006058[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006058, 0x00010000U ,0x00000000U), + // .. .. reg_ddrc_rd_odt_delay = 0x3 + // .. .. ==> 0XF800605C[3:0] = 0x00000003U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000003U + // .. .. reg_ddrc_wr_odt_delay = 0x0 + // .. .. ==> 0XF800605C[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. reg_ddrc_rd_odt_hold = 0x0 + // .. .. ==> 0XF800605C[11:8] = 0x00000000U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000000U + // .. .. reg_ddrc_wr_odt_hold = 0x5 + // .. .. ==> 0XF800605C[15:12] = 0x00000005U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00005000U + // .. .. + EMIT_MASKWRITE(0XF800605C, 0x0000FFFFU ,0x00005003U), + // .. .. reg_ddrc_pageclose = 0x0 + // .. .. ==> 0XF8006060[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_lpr_num_entries = 0x1f + // .. .. ==> 0XF8006060[6:1] = 0x0000001FU + // .. .. ==> MASK : 0x0000007EU VAL : 0x0000003EU + // .. .. reg_ddrc_auto_pre_en = 0x0 + // .. .. ==> 0XF8006060[7:7] = 0x00000000U + // .. .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. .. reg_ddrc_refresh_update_level = 0x0 + // .. .. ==> 0XF8006060[8:8] = 0x00000000U + // .. .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. .. reg_ddrc_dis_wc = 0x0 + // .. .. ==> 0XF8006060[9:9] = 0x00000000U + // .. .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. .. reg_ddrc_dis_collision_page_opt = 0x0 + // .. .. ==> 0XF8006060[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_ddrc_selfref_en = 0x0 + // .. .. ==> 0XF8006060[12:12] = 0x00000000U + // .. .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006060, 0x000017FFU ,0x0000003EU), + // .. .. reg_ddrc_go2critical_hysteresis = 0x0 + // .. .. ==> 0XF8006064[12:5] = 0x00000000U + // .. .. ==> MASK : 0x00001FE0U VAL : 0x00000000U + // .. .. reg_arb_go2critical_en = 0x1 + // .. .. ==> 0XF8006064[17:17] = 0x00000001U + // .. .. ==> MASK : 0x00020000U VAL : 0x00020000U + // .. .. + EMIT_MASKWRITE(0XF8006064, 0x00021FE0U ,0x00020000U), + // .. .. reg_ddrc_wrlvl_ww = 0x41 + // .. .. ==> 0XF8006068[7:0] = 0x00000041U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000041U + // .. .. reg_ddrc_rdlvl_rr = 0x41 + // .. .. ==> 0XF8006068[15:8] = 0x00000041U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00004100U + // .. .. reg_ddrc_dfi_t_wlmrd = 0x28 + // .. .. ==> 0XF8006068[25:16] = 0x00000028U + // .. .. ==> MASK : 0x03FF0000U VAL : 0x00280000U + // .. .. + EMIT_MASKWRITE(0XF8006068, 0x03FFFFFFU ,0x00284141U), + // .. .. dfi_t_ctrlupd_interval_min_x1024 = 0x10 + // .. .. ==> 0XF800606C[7:0] = 0x00000010U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000010U + // .. .. dfi_t_ctrlupd_interval_max_x1024 = 0x16 + // .. .. ==> 0XF800606C[15:8] = 0x00000016U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00001600U + // .. .. + EMIT_MASKWRITE(0XF800606C, 0x0000FFFFU ,0x00001610U), + // .. .. reg_ddrc_dfi_t_ctrl_delay = 0x1 + // .. .. ==> 0XF8006078[3:0] = 0x00000001U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000001U + // .. .. reg_ddrc_dfi_t_dram_clk_disable = 0x1 + // .. .. ==> 0XF8006078[7:4] = 0x00000001U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000010U + // .. .. reg_ddrc_dfi_t_dram_clk_enable = 0x1 + // .. .. ==> 0XF8006078[11:8] = 0x00000001U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000100U + // .. .. reg_ddrc_t_cksre = 0x6 + // .. .. ==> 0XF8006078[15:12] = 0x00000006U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00006000U + // .. .. reg_ddrc_t_cksrx = 0x6 + // .. .. ==> 0XF8006078[19:16] = 0x00000006U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00060000U + // .. .. reg_ddrc_t_ckesr = 0x4 + // .. .. ==> 0XF8006078[25:20] = 0x00000004U + // .. .. ==> MASK : 0x03F00000U VAL : 0x00400000U + // .. .. + EMIT_MASKWRITE(0XF8006078, 0x03FFFFFFU ,0x00466111U), + // .. .. reg_ddrc_t_ckpde = 0x2 + // .. .. ==> 0XF800607C[3:0] = 0x00000002U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000002U + // .. .. reg_ddrc_t_ckpdx = 0x2 + // .. .. ==> 0XF800607C[7:4] = 0x00000002U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000020U + // .. .. reg_ddrc_t_ckdpde = 0x2 + // .. .. ==> 0XF800607C[11:8] = 0x00000002U + // .. .. ==> MASK : 0x00000F00U VAL : 0x00000200U + // .. .. reg_ddrc_t_ckdpdx = 0x2 + // .. .. ==> 0XF800607C[15:12] = 0x00000002U + // .. .. ==> MASK : 0x0000F000U VAL : 0x00002000U + // .. .. reg_ddrc_t_ckcsx = 0x3 + // .. .. ==> 0XF800607C[19:16] = 0x00000003U + // .. .. ==> MASK : 0x000F0000U VAL : 0x00030000U + // .. .. + EMIT_MASKWRITE(0XF800607C, 0x000FFFFFU ,0x00032222U), + // .. .. reg_ddrc_dis_auto_zq = 0x0 + // .. .. ==> 0XF80060A4[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_ddr3 = 0x1 + // .. .. ==> 0XF80060A4[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. reg_ddrc_t_mod = 0x200 + // .. .. ==> 0XF80060A4[11:2] = 0x00000200U + // .. .. ==> MASK : 0x00000FFCU VAL : 0x00000800U + // .. .. reg_ddrc_t_zq_long_nop = 0x200 + // .. .. ==> 0XF80060A4[21:12] = 0x00000200U + // .. .. ==> MASK : 0x003FF000U VAL : 0x00200000U + // .. .. reg_ddrc_t_zq_short_nop = 0x40 + // .. .. ==> 0XF80060A4[31:22] = 0x00000040U + // .. .. ==> MASK : 0xFFC00000U VAL : 0x10000000U + // .. .. + EMIT_MASKWRITE(0XF80060A4, 0xFFFFFFFFU ,0x10200802U), + // .. .. t_zq_short_interval_x1024 = 0xc845 + // .. .. ==> 0XF80060A8[19:0] = 0x0000C845U + // .. .. ==> MASK : 0x000FFFFFU VAL : 0x0000C845U + // .. .. dram_rstn_x1024 = 0x67 + // .. .. ==> 0XF80060A8[27:20] = 0x00000067U + // .. .. ==> MASK : 0x0FF00000U VAL : 0x06700000U + // .. .. + EMIT_MASKWRITE(0XF80060A8, 0x0FFFFFFFU ,0x0670C845U), + // .. .. deeppowerdown_en = 0x0 + // .. .. ==> 0XF80060AC[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. deeppowerdown_to_x1024 = 0xff + // .. .. ==> 0XF80060AC[8:1] = 0x000000FFU + // .. .. ==> MASK : 0x000001FEU VAL : 0x000001FEU + // .. .. + EMIT_MASKWRITE(0XF80060AC, 0x000001FFU ,0x000001FEU), + // .. .. dfi_wrlvl_max_x1024 = 0xfff + // .. .. ==> 0XF80060B0[11:0] = 0x00000FFFU + // .. .. ==> MASK : 0x00000FFFU VAL : 0x00000FFFU + // .. .. dfi_rdlvl_max_x1024 = 0xfff + // .. .. ==> 0XF80060B0[23:12] = 0x00000FFFU + // .. .. ==> MASK : 0x00FFF000U VAL : 0x00FFF000U + // .. .. ddrc_reg_twrlvl_max_error = 0x0 + // .. .. ==> 0XF80060B0[24:24] = 0x00000000U + // .. .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. .. ddrc_reg_trdlvl_max_error = 0x0 + // .. .. ==> 0XF80060B0[25:25] = 0x00000000U + // .. .. ==> MASK : 0x02000000U VAL : 0x00000000U + // .. .. reg_ddrc_dfi_wr_level_en = 0x1 + // .. .. ==> 0XF80060B0[26:26] = 0x00000001U + // .. .. ==> MASK : 0x04000000U VAL : 0x04000000U + // .. .. reg_ddrc_dfi_rd_dqs_gate_level = 0x1 + // .. .. ==> 0XF80060B0[27:27] = 0x00000001U + // .. .. ==> MASK : 0x08000000U VAL : 0x08000000U + // .. .. reg_ddrc_dfi_rd_data_eye_train = 0x1 + // .. .. ==> 0XF80060B0[28:28] = 0x00000001U + // .. .. ==> MASK : 0x10000000U VAL : 0x10000000U + // .. .. + EMIT_MASKWRITE(0XF80060B0, 0x1FFFFFFFU ,0x1CFFFFFFU), + // .. .. reg_ddrc_skip_ocd = 0x1 + // .. .. ==> 0XF80060B4[9:9] = 0x00000001U + // .. .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. .. + EMIT_MASKWRITE(0XF80060B4, 0x00000200U ,0x00000200U), + // .. .. reg_ddrc_dfi_t_rddata_en = 0x6 + // .. .. ==> 0XF80060B8[4:0] = 0x00000006U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000006U + // .. .. reg_ddrc_dfi_t_ctrlup_min = 0x3 + // .. .. ==> 0XF80060B8[14:5] = 0x00000003U + // .. .. ==> MASK : 0x00007FE0U VAL : 0x00000060U + // .. .. reg_ddrc_dfi_t_ctrlup_max = 0x40 + // .. .. ==> 0XF80060B8[24:15] = 0x00000040U + // .. .. ==> MASK : 0x01FF8000U VAL : 0x00200000U + // .. .. + EMIT_MASKWRITE(0XF80060B8, 0x01FFFFFFU ,0x00200066U), + // .. .. START: RESET ECC ERROR + // .. .. Clear_Uncorrectable_DRAM_ECC_error = 1 + // .. .. ==> 0XF80060C4[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. Clear_Correctable_DRAM_ECC_error = 1 + // .. .. ==> 0XF80060C4[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. + EMIT_MASKWRITE(0XF80060C4, 0x00000003U ,0x00000003U), + // .. .. FINISH: RESET ECC ERROR + // .. .. Clear_Uncorrectable_DRAM_ECC_error = 0x0 + // .. .. ==> 0XF80060C4[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. Clear_Correctable_DRAM_ECC_error = 0x0 + // .. .. ==> 0XF80060C4[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80060C4, 0x00000003U ,0x00000000U), + // .. .. CORR_ECC_LOG_VALID = 0x0 + // .. .. ==> 0XF80060C8[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. ECC_CORRECTED_BIT_NUM = 0x0 + // .. .. ==> 0XF80060C8[7:1] = 0x00000000U + // .. .. ==> MASK : 0x000000FEU VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80060C8, 0x000000FFU ,0x00000000U), + // .. .. UNCORR_ECC_LOG_VALID = 0x0 + // .. .. ==> 0XF80060DC[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80060DC, 0x00000001U ,0x00000000U), + // .. .. STAT_NUM_CORR_ERR = 0x0 + // .. .. ==> 0XF80060F0[15:8] = 0x00000000U + // .. .. ==> MASK : 0x0000FF00U VAL : 0x00000000U + // .. .. STAT_NUM_UNCORR_ERR = 0x0 + // .. .. ==> 0XF80060F0[7:0] = 0x00000000U + // .. .. ==> MASK : 0x000000FFU VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80060F0, 0x0000FFFFU ,0x00000000U), + // .. .. reg_ddrc_ecc_mode = 0x0 + // .. .. ==> 0XF80060F4[2:0] = 0x00000000U + // .. .. ==> MASK : 0x00000007U VAL : 0x00000000U + // .. .. reg_ddrc_dis_scrub = 0x1 + // .. .. ==> 0XF80060F4[3:3] = 0x00000001U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. .. + EMIT_MASKWRITE(0XF80060F4, 0x0000000FU ,0x00000008U), + // .. .. reg_phy_dif_on = 0x0 + // .. .. ==> 0XF8006114[3:0] = 0x00000000U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000000U + // .. .. reg_phy_dif_off = 0x0 + // .. .. ==> 0XF8006114[7:4] = 0x00000000U + // .. .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006114, 0x000000FFU ,0x00000000U), + // .. .. reg_phy_data_slice_in_use = 0x1 + // .. .. ==> 0XF8006118[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. reg_phy_rdlvl_inc_mode = 0x0 + // .. .. ==> 0XF8006118[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_phy_gatelvl_inc_mode = 0x0 + // .. .. ==> 0XF8006118[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. reg_phy_wrlvl_inc_mode = 0x0 + // .. .. ==> 0XF8006118[3:3] = 0x00000000U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. .. reg_phy_bist_shift_dq = 0x0 + // .. .. ==> 0XF8006118[14:6] = 0x00000000U + // .. .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. .. reg_phy_bist_err_clr = 0x0 + // .. .. ==> 0XF8006118[23:15] = 0x00000000U + // .. .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. .. reg_phy_dq_offset = 0x40 + // .. .. ==> 0XF8006118[30:24] = 0x00000040U + // .. .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. .. + EMIT_MASKWRITE(0XF8006118, 0x7FFFFFCFU ,0x40000001U), + // .. .. reg_phy_data_slice_in_use = 0x1 + // .. .. ==> 0XF800611C[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. reg_phy_rdlvl_inc_mode = 0x0 + // .. .. ==> 0XF800611C[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_phy_gatelvl_inc_mode = 0x0 + // .. .. ==> 0XF800611C[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. reg_phy_wrlvl_inc_mode = 0x0 + // .. .. ==> 0XF800611C[3:3] = 0x00000000U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. .. reg_phy_bist_shift_dq = 0x0 + // .. .. ==> 0XF800611C[14:6] = 0x00000000U + // .. .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. .. reg_phy_bist_err_clr = 0x0 + // .. .. ==> 0XF800611C[23:15] = 0x00000000U + // .. .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. .. reg_phy_dq_offset = 0x40 + // .. .. ==> 0XF800611C[30:24] = 0x00000040U + // .. .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. .. + EMIT_MASKWRITE(0XF800611C, 0x7FFFFFCFU ,0x40000001U), + // .. .. reg_phy_data_slice_in_use = 0x1 + // .. .. ==> 0XF8006120[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. reg_phy_rdlvl_inc_mode = 0x0 + // .. .. ==> 0XF8006120[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_phy_gatelvl_inc_mode = 0x0 + // .. .. ==> 0XF8006120[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. reg_phy_wrlvl_inc_mode = 0x0 + // .. .. ==> 0XF8006120[3:3] = 0x00000000U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. .. reg_phy_bist_shift_dq = 0x0 + // .. .. ==> 0XF8006120[14:6] = 0x00000000U + // .. .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. .. reg_phy_bist_err_clr = 0x0 + // .. .. ==> 0XF8006120[23:15] = 0x00000000U + // .. .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. .. reg_phy_dq_offset = 0x40 + // .. .. ==> 0XF8006120[30:24] = 0x00000040U + // .. .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. .. + EMIT_MASKWRITE(0XF8006120, 0x7FFFFFCFU ,0x40000001U), + // .. .. reg_phy_data_slice_in_use = 0x1 + // .. .. ==> 0XF8006124[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. reg_phy_rdlvl_inc_mode = 0x0 + // .. .. ==> 0XF8006124[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_phy_gatelvl_inc_mode = 0x0 + // .. .. ==> 0XF8006124[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. reg_phy_wrlvl_inc_mode = 0x0 + // .. .. ==> 0XF8006124[3:3] = 0x00000000U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. .. reg_phy_bist_shift_dq = 0x0 + // .. .. ==> 0XF8006124[14:6] = 0x00000000U + // .. .. ==> MASK : 0x00007FC0U VAL : 0x00000000U + // .. .. reg_phy_bist_err_clr = 0x0 + // .. .. ==> 0XF8006124[23:15] = 0x00000000U + // .. .. ==> MASK : 0x00FF8000U VAL : 0x00000000U + // .. .. reg_phy_dq_offset = 0x40 + // .. .. ==> 0XF8006124[30:24] = 0x00000040U + // .. .. ==> MASK : 0x7F000000U VAL : 0x40000000U + // .. .. + EMIT_MASKWRITE(0XF8006124, 0x7FFFFFCFU ,0x40000001U), + // .. .. reg_phy_wrlvl_init_ratio = 0x0 + // .. .. ==> 0XF800612C[9:0] = 0x00000000U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. .. reg_phy_gatelvl_init_ratio = 0x8f + // .. .. ==> 0XF800612C[19:10] = 0x0000008FU + // .. .. ==> MASK : 0x000FFC00U VAL : 0x00023C00U + // .. .. + EMIT_MASKWRITE(0XF800612C, 0x000FFFFFU ,0x00023C00U), + // .. .. reg_phy_wrlvl_init_ratio = 0x0 + // .. .. ==> 0XF8006130[9:0] = 0x00000000U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. .. reg_phy_gatelvl_init_ratio = 0x8a + // .. .. ==> 0XF8006130[19:10] = 0x0000008AU + // .. .. ==> MASK : 0x000FFC00U VAL : 0x00022800U + // .. .. + EMIT_MASKWRITE(0XF8006130, 0x000FFFFFU ,0x00022800U), + // .. .. reg_phy_wrlvl_init_ratio = 0x0 + // .. .. ==> 0XF8006134[9:0] = 0x00000000U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. .. reg_phy_gatelvl_init_ratio = 0x8b + // .. .. ==> 0XF8006134[19:10] = 0x0000008BU + // .. .. ==> MASK : 0x000FFC00U VAL : 0x00022C00U + // .. .. + EMIT_MASKWRITE(0XF8006134, 0x000FFFFFU ,0x00022C00U), + // .. .. reg_phy_wrlvl_init_ratio = 0x0 + // .. .. ==> 0XF8006138[9:0] = 0x00000000U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000000U + // .. .. reg_phy_gatelvl_init_ratio = 0x92 + // .. .. ==> 0XF8006138[19:10] = 0x00000092U + // .. .. ==> MASK : 0x000FFC00U VAL : 0x00024800U + // .. .. + EMIT_MASKWRITE(0XF8006138, 0x000FFFFFU ,0x00024800U), + // .. .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. .. ==> 0XF8006140[9:0] = 0x00000035U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. .. reg_phy_rd_dqs_slave_force = 0x0 + // .. .. ==> 0XF8006140[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. .. ==> 0XF8006140[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006140, 0x000FFFFFU ,0x00000035U), + // .. .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. .. ==> 0XF8006144[9:0] = 0x00000035U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. .. reg_phy_rd_dqs_slave_force = 0x0 + // .. .. ==> 0XF8006144[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. .. ==> 0XF8006144[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006144, 0x000FFFFFU ,0x00000035U), + // .. .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. .. ==> 0XF8006148[9:0] = 0x00000035U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. .. reg_phy_rd_dqs_slave_force = 0x0 + // .. .. ==> 0XF8006148[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. .. ==> 0XF8006148[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006148, 0x000FFFFFU ,0x00000035U), + // .. .. reg_phy_rd_dqs_slave_ratio = 0x35 + // .. .. ==> 0XF800614C[9:0] = 0x00000035U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000035U + // .. .. reg_phy_rd_dqs_slave_force = 0x0 + // .. .. ==> 0XF800614C[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_rd_dqs_slave_delay = 0x0 + // .. .. ==> 0XF800614C[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800614C, 0x000FFFFFU ,0x00000035U), + // .. .. reg_phy_wr_dqs_slave_ratio = 0x77 + // .. .. ==> 0XF8006154[9:0] = 0x00000077U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000077U + // .. .. reg_phy_wr_dqs_slave_force = 0x0 + // .. .. ==> 0XF8006154[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. .. ==> 0XF8006154[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006154, 0x000FFFFFU ,0x00000077U), + // .. .. reg_phy_wr_dqs_slave_ratio = 0x7c + // .. .. ==> 0XF8006158[9:0] = 0x0000007CU + // .. .. ==> MASK : 0x000003FFU VAL : 0x0000007CU + // .. .. reg_phy_wr_dqs_slave_force = 0x0 + // .. .. ==> 0XF8006158[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. .. ==> 0XF8006158[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006158, 0x000FFFFFU ,0x0000007CU), + // .. .. reg_phy_wr_dqs_slave_ratio = 0x7c + // .. .. ==> 0XF800615C[9:0] = 0x0000007CU + // .. .. ==> MASK : 0x000003FFU VAL : 0x0000007CU + // .. .. reg_phy_wr_dqs_slave_force = 0x0 + // .. .. ==> 0XF800615C[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. .. ==> 0XF800615C[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800615C, 0x000FFFFFU ,0x0000007CU), + // .. .. reg_phy_wr_dqs_slave_ratio = 0x75 + // .. .. ==> 0XF8006160[9:0] = 0x00000075U + // .. .. ==> MASK : 0x000003FFU VAL : 0x00000075U + // .. .. reg_phy_wr_dqs_slave_force = 0x0 + // .. .. ==> 0XF8006160[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_dqs_slave_delay = 0x0 + // .. .. ==> 0XF8006160[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006160, 0x000FFFFFU ,0x00000075U), + // .. .. reg_phy_fifo_we_slave_ratio = 0xe4 + // .. .. ==> 0XF8006168[10:0] = 0x000000E4U + // .. .. ==> MASK : 0x000007FFU VAL : 0x000000E4U + // .. .. reg_phy_fifo_we_in_force = 0x0 + // .. .. ==> 0XF8006168[11:11] = 0x00000000U + // .. .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. .. reg_phy_fifo_we_in_delay = 0x0 + // .. .. ==> 0XF8006168[20:12] = 0x00000000U + // .. .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006168, 0x001FFFFFU ,0x000000E4U), + // .. .. reg_phy_fifo_we_slave_ratio = 0xdf + // .. .. ==> 0XF800616C[10:0] = 0x000000DFU + // .. .. ==> MASK : 0x000007FFU VAL : 0x000000DFU + // .. .. reg_phy_fifo_we_in_force = 0x0 + // .. .. ==> 0XF800616C[11:11] = 0x00000000U + // .. .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. .. reg_phy_fifo_we_in_delay = 0x0 + // .. .. ==> 0XF800616C[20:12] = 0x00000000U + // .. .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800616C, 0x001FFFFFU ,0x000000DFU), + // .. .. reg_phy_fifo_we_slave_ratio = 0xe0 + // .. .. ==> 0XF8006170[10:0] = 0x000000E0U + // .. .. ==> MASK : 0x000007FFU VAL : 0x000000E0U + // .. .. reg_phy_fifo_we_in_force = 0x0 + // .. .. ==> 0XF8006170[11:11] = 0x00000000U + // .. .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. .. reg_phy_fifo_we_in_delay = 0x0 + // .. .. ==> 0XF8006170[20:12] = 0x00000000U + // .. .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006170, 0x001FFFFFU ,0x000000E0U), + // .. .. reg_phy_fifo_we_slave_ratio = 0xe7 + // .. .. ==> 0XF8006174[10:0] = 0x000000E7U + // .. .. ==> MASK : 0x000007FFU VAL : 0x000000E7U + // .. .. reg_phy_fifo_we_in_force = 0x0 + // .. .. ==> 0XF8006174[11:11] = 0x00000000U + // .. .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. .. reg_phy_fifo_we_in_delay = 0x0 + // .. .. ==> 0XF8006174[20:12] = 0x00000000U + // .. .. ==> MASK : 0x001FF000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006174, 0x001FFFFFU ,0x000000E7U), + // .. .. reg_phy_wr_data_slave_ratio = 0xb7 + // .. .. ==> 0XF800617C[9:0] = 0x000000B7U + // .. .. ==> MASK : 0x000003FFU VAL : 0x000000B7U + // .. .. reg_phy_wr_data_slave_force = 0x0 + // .. .. ==> 0XF800617C[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_data_slave_delay = 0x0 + // .. .. ==> 0XF800617C[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800617C, 0x000FFFFFU ,0x000000B7U), + // .. .. reg_phy_wr_data_slave_ratio = 0xbc + // .. .. ==> 0XF8006180[9:0] = 0x000000BCU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000000BCU + // .. .. reg_phy_wr_data_slave_force = 0x0 + // .. .. ==> 0XF8006180[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_data_slave_delay = 0x0 + // .. .. ==> 0XF8006180[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006180, 0x000FFFFFU ,0x000000BCU), + // .. .. reg_phy_wr_data_slave_ratio = 0xbc + // .. .. ==> 0XF8006184[9:0] = 0x000000BCU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000000BCU + // .. .. reg_phy_wr_data_slave_force = 0x0 + // .. .. ==> 0XF8006184[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_data_slave_delay = 0x0 + // .. .. ==> 0XF8006184[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006184, 0x000FFFFFU ,0x000000BCU), + // .. .. reg_phy_wr_data_slave_ratio = 0xb5 + // .. .. ==> 0XF8006188[9:0] = 0x000000B5U + // .. .. ==> MASK : 0x000003FFU VAL : 0x000000B5U + // .. .. reg_phy_wr_data_slave_force = 0x0 + // .. .. ==> 0XF8006188[10:10] = 0x00000000U + // .. .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. .. reg_phy_wr_data_slave_delay = 0x0 + // .. .. ==> 0XF8006188[19:11] = 0x00000000U + // .. .. ==> MASK : 0x000FF800U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006188, 0x000FFFFFU ,0x000000B5U), + // .. .. reg_phy_bl2 = 0x0 + // .. .. ==> 0XF8006190[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_phy_at_spd_atpg = 0x0 + // .. .. ==> 0XF8006190[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. reg_phy_bist_enable = 0x0 + // .. .. ==> 0XF8006190[3:3] = 0x00000000U + // .. .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. .. reg_phy_bist_force_err = 0x0 + // .. .. ==> 0XF8006190[4:4] = 0x00000000U + // .. .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. .. reg_phy_bist_mode = 0x0 + // .. .. ==> 0XF8006190[6:5] = 0x00000000U + // .. .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. .. reg_phy_invert_clkout = 0x1 + // .. .. ==> 0XF8006190[7:7] = 0x00000001U + // .. .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. .. reg_phy_sel_logic = 0x0 + // .. .. ==> 0XF8006190[9:9] = 0x00000000U + // .. .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. .. reg_phy_ctrl_slave_ratio = 0x100 + // .. .. ==> 0XF8006190[19:10] = 0x00000100U + // .. .. ==> MASK : 0x000FFC00U VAL : 0x00040000U + // .. .. reg_phy_ctrl_slave_force = 0x0 + // .. .. ==> 0XF8006190[20:20] = 0x00000000U + // .. .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. .. reg_phy_ctrl_slave_delay = 0x0 + // .. .. ==> 0XF8006190[27:21] = 0x00000000U + // .. .. ==> MASK : 0x0FE00000U VAL : 0x00000000U + // .. .. reg_phy_lpddr = 0x0 + // .. .. ==> 0XF8006190[29:29] = 0x00000000U + // .. .. ==> MASK : 0x20000000U VAL : 0x00000000U + // .. .. reg_phy_cmd_latency = 0x0 + // .. .. ==> 0XF8006190[30:30] = 0x00000000U + // .. .. ==> MASK : 0x40000000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006190, 0x6FFFFEFEU ,0x00040080U), + // .. .. reg_phy_wr_rl_delay = 0x2 + // .. .. ==> 0XF8006194[4:0] = 0x00000002U + // .. .. ==> MASK : 0x0000001FU VAL : 0x00000002U + // .. .. reg_phy_rd_rl_delay = 0x4 + // .. .. ==> 0XF8006194[9:5] = 0x00000004U + // .. .. ==> MASK : 0x000003E0U VAL : 0x00000080U + // .. .. reg_phy_dll_lock_diff = 0xf + // .. .. ==> 0XF8006194[13:10] = 0x0000000FU + // .. .. ==> MASK : 0x00003C00U VAL : 0x00003C00U + // .. .. reg_phy_use_wr_level = 0x1 + // .. .. ==> 0XF8006194[14:14] = 0x00000001U + // .. .. ==> MASK : 0x00004000U VAL : 0x00004000U + // .. .. reg_phy_use_rd_dqs_gate_level = 0x1 + // .. .. ==> 0XF8006194[15:15] = 0x00000001U + // .. .. ==> MASK : 0x00008000U VAL : 0x00008000U + // .. .. reg_phy_use_rd_data_eye_level = 0x1 + // .. .. ==> 0XF8006194[16:16] = 0x00000001U + // .. .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. .. reg_phy_dis_calib_rst = 0x0 + // .. .. ==> 0XF8006194[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_phy_ctrl_slave_delay = 0x0 + // .. .. ==> 0XF8006194[19:18] = 0x00000000U + // .. .. ==> MASK : 0x000C0000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006194, 0x000FFFFFU ,0x0001FC82U), + // .. .. reg_arb_page_addr_mask = 0x0 + // .. .. ==> 0XF8006204[31:0] = 0x00000000U + // .. .. ==> MASK : 0xFFFFFFFFU VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006204, 0xFFFFFFFFU ,0x00000000U), + // .. .. reg_arb_pri_wr_portn = 0x3ff + // .. .. ==> 0XF8006208[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_wr_portn = 0x0 + // .. .. ==> 0XF8006208[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. .. ==> 0XF8006208[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. .. ==> 0XF8006208[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006208, 0x000703FFU ,0x000003FFU), + // .. .. reg_arb_pri_wr_portn = 0x3ff + // .. .. ==> 0XF800620C[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_wr_portn = 0x0 + // .. .. ==> 0XF800620C[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. .. ==> 0XF800620C[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. .. ==> 0XF800620C[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800620C, 0x000703FFU ,0x000003FFU), + // .. .. reg_arb_pri_wr_portn = 0x3ff + // .. .. ==> 0XF8006210[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_wr_portn = 0x0 + // .. .. ==> 0XF8006210[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. .. ==> 0XF8006210[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. .. ==> 0XF8006210[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006210, 0x000703FFU ,0x000003FFU), + // .. .. reg_arb_pri_wr_portn = 0x3ff + // .. .. ==> 0XF8006214[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_wr_portn = 0x0 + // .. .. ==> 0XF8006214[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_wr_portn = 0x0 + // .. .. ==> 0XF8006214[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_wr_portn = 0x0 + // .. .. ==> 0XF8006214[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006214, 0x000703FFU ,0x000003FFU), + // .. .. reg_arb_pri_rd_portn = 0x3ff + // .. .. ==> 0XF8006218[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_rd_portn = 0x0 + // .. .. ==> 0XF8006218[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. .. ==> 0XF8006218[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. .. ==> 0XF8006218[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. reg_arb_set_hpr_rd_portn = 0x0 + // .. .. ==> 0XF8006218[19:19] = 0x00000000U + // .. .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006218, 0x000F03FFU ,0x000003FFU), + // .. .. reg_arb_pri_rd_portn = 0x3ff + // .. .. ==> 0XF800621C[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_rd_portn = 0x0 + // .. .. ==> 0XF800621C[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. .. ==> 0XF800621C[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. .. ==> 0XF800621C[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. reg_arb_set_hpr_rd_portn = 0x0 + // .. .. ==> 0XF800621C[19:19] = 0x00000000U + // .. .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF800621C, 0x000F03FFU ,0x000003FFU), + // .. .. reg_arb_pri_rd_portn = 0x3ff + // .. .. ==> 0XF8006220[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_rd_portn = 0x0 + // .. .. ==> 0XF8006220[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. .. ==> 0XF8006220[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. .. ==> 0XF8006220[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. reg_arb_set_hpr_rd_portn = 0x0 + // .. .. ==> 0XF8006220[19:19] = 0x00000000U + // .. .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006220, 0x000F03FFU ,0x000003FFU), + // .. .. reg_arb_pri_rd_portn = 0x3ff + // .. .. ==> 0XF8006224[9:0] = 0x000003FFU + // .. .. ==> MASK : 0x000003FFU VAL : 0x000003FFU + // .. .. reg_arb_disable_aging_rd_portn = 0x0 + // .. .. ==> 0XF8006224[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. reg_arb_disable_urgent_rd_portn = 0x0 + // .. .. ==> 0XF8006224[17:17] = 0x00000000U + // .. .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. .. reg_arb_dis_page_match_rd_portn = 0x0 + // .. .. ==> 0XF8006224[18:18] = 0x00000000U + // .. .. ==> MASK : 0x00040000U VAL : 0x00000000U + // .. .. reg_arb_set_hpr_rd_portn = 0x0 + // .. .. ==> 0XF8006224[19:19] = 0x00000000U + // .. .. ==> MASK : 0x00080000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006224, 0x000F03FFU ,0x000003FFU), + // .. .. reg_ddrc_lpddr2 = 0x0 + // .. .. ==> 0XF80062A8[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. reg_ddrc_derate_enable = 0x0 + // .. .. ==> 0XF80062A8[2:2] = 0x00000000U + // .. .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. .. reg_ddrc_mr4_margin = 0x0 + // .. .. ==> 0XF80062A8[11:4] = 0x00000000U + // .. .. ==> MASK : 0x00000FF0U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80062A8, 0x00000FF5U ,0x00000000U), + // .. .. reg_ddrc_mr4_read_interval = 0x0 + // .. .. ==> 0XF80062AC[31:0] = 0x00000000U + // .. .. ==> MASK : 0xFFFFFFFFU VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF80062AC, 0xFFFFFFFFU ,0x00000000U), + // .. .. reg_ddrc_min_stable_clock_x1 = 0x5 + // .. .. ==> 0XF80062B0[3:0] = 0x00000005U + // .. .. ==> MASK : 0x0000000FU VAL : 0x00000005U + // .. .. reg_ddrc_idle_after_reset_x32 = 0x12 + // .. .. ==> 0XF80062B0[11:4] = 0x00000012U + // .. .. ==> MASK : 0x00000FF0U VAL : 0x00000120U + // .. .. reg_ddrc_t_mrw = 0x5 + // .. .. ==> 0XF80062B0[21:12] = 0x00000005U + // .. .. ==> MASK : 0x003FF000U VAL : 0x00005000U + // .. .. + EMIT_MASKWRITE(0XF80062B0, 0x003FFFFFU ,0x00005125U), + // .. .. reg_ddrc_max_auto_init_x1024 = 0xa6 + // .. .. ==> 0XF80062B4[7:0] = 0x000000A6U + // .. .. ==> MASK : 0x000000FFU VAL : 0x000000A6U + // .. .. reg_ddrc_dev_zqinit_x32 = 0x12 + // .. .. ==> 0XF80062B4[17:8] = 0x00000012U + // .. .. ==> MASK : 0x0003FF00U VAL : 0x00001200U + // .. .. + EMIT_MASKWRITE(0XF80062B4, 0x0003FFFFU ,0x000012A6U), + // .. .. START: POLL ON DCI STATUS + // .. .. DONE = 1 + // .. .. ==> 0XF8000B74[13:13] = 0x00000001U + // .. .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. .. + EMIT_MASKPOLL(0XF8000B74, 0x00002000U), + // .. .. FINISH: POLL ON DCI STATUS + // .. .. START: UNLOCK DDR + // .. .. reg_ddrc_soft_rstb = 0x1 + // .. .. ==> 0XF8006000[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. reg_ddrc_powerdown_en = 0x0 + // .. .. ==> 0XF8006000[1:1] = 0x00000000U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. .. reg_ddrc_data_bus_width = 0x0 + // .. .. ==> 0XF8006000[3:2] = 0x00000000U + // .. .. ==> MASK : 0x0000000CU VAL : 0x00000000U + // .. .. reg_ddrc_burst8_refresh = 0x0 + // .. .. ==> 0XF8006000[6:4] = 0x00000000U + // .. .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. .. reg_ddrc_rdwr_idle_gap = 1 + // .. .. ==> 0XF8006000[13:7] = 0x00000001U + // .. .. ==> MASK : 0x00003F80U VAL : 0x00000080U + // .. .. reg_ddrc_dis_rd_bypass = 0x0 + // .. .. ==> 0XF8006000[14:14] = 0x00000000U + // .. .. ==> MASK : 0x00004000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_act_bypass = 0x0 + // .. .. ==> 0XF8006000[15:15] = 0x00000000U + // .. .. ==> MASK : 0x00008000U VAL : 0x00000000U + // .. .. reg_ddrc_dis_auto_refresh = 0x0 + // .. .. ==> 0XF8006000[16:16] = 0x00000000U + // .. .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8006000, 0x0001FFFFU ,0x00000081U), + // .. .. FINISH: UNLOCK DDR + // .. .. START: CHECK DDR STATUS + // .. .. ddrc_reg_operating_mode = 1 + // .. .. ==> 0XF8006054[2:0] = 0x00000001U + // .. .. ==> MASK : 0x00000007U VAL : 0x00000001U + // .. .. + EMIT_MASKPOLL(0XF8006054, 0x00000007U), + // .. .. FINISH: CHECK DDR STATUS + // .. FINISH: DDR INITIALIZATION + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_mio_init_data_3_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: OCM REMAPPING + // .. VREF_EN = 0x1 + // .. ==> 0XF8000B00[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. VREF_SEL = 0x0 + // .. ==> 0XF8000B00[6:4] = 0x00000000U + // .. ==> MASK : 0x00000070U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B00, 0x00000071U ,0x00000001U), + // .. FINISH: OCM REMAPPING + // .. START: DDRIOB SETTINGS + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B40[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE_B = 0x0 + // .. ==> 0XF8000B40[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B40[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCI_TYPE = 0x0 + // .. ==> 0XF8000B40[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B40[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B40[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B40[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B40[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B40, 0x00000FFEU ,0x00000600U), + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B44[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE_B = 0x0 + // .. ==> 0XF8000B44[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B44[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCI_TYPE = 0x0 + // .. ==> 0XF8000B44[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B44[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B44[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B44[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B44[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B44, 0x00000FFEU ,0x00000600U), + // .. INP_TYPE = 0x1 + // .. ==> 0XF8000B48[2:1] = 0x00000001U + // .. ==> MASK : 0x00000006U VAL : 0x00000002U + // .. DCI_UPDATE_B = 0x0 + // .. ==> 0XF8000B48[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B48[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCI_TYPE = 0x3 + // .. ==> 0XF8000B48[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B48[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B48[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B48[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B48[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B48, 0x00000FFEU ,0x00000672U), + // .. INP_TYPE = 0x1 + // .. ==> 0XF8000B4C[2:1] = 0x00000001U + // .. ==> MASK : 0x00000006U VAL : 0x00000002U + // .. DCI_UPDATE_B = 0x0 + // .. ==> 0XF8000B4C[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B4C[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCI_TYPE = 0x3 + // .. ==> 0XF8000B4C[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B4C[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B4C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B4C[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B4C[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B4C, 0x00000FFEU ,0x00000672U), + // .. INP_TYPE = 0x2 + // .. ==> 0XF8000B50[2:1] = 0x00000002U + // .. ==> MASK : 0x00000006U VAL : 0x00000004U + // .. DCI_UPDATE_B = 0x0 + // .. ==> 0XF8000B50[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B50[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCI_TYPE = 0x3 + // .. ==> 0XF8000B50[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B50[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B50[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B50[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B50[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B50, 0x00000FFEU ,0x00000674U), + // .. INP_TYPE = 0x2 + // .. ==> 0XF8000B54[2:1] = 0x00000002U + // .. ==> MASK : 0x00000006U VAL : 0x00000004U + // .. DCI_UPDATE_B = 0x0 + // .. ==> 0XF8000B54[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x1 + // .. ==> 0XF8000B54[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. DCI_TYPE = 0x3 + // .. ==> 0XF8000B54[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. IBUF_DISABLE_MODE = 0 + // .. ==> 0XF8000B54[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0 + // .. ==> 0XF8000B54[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B54[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B54[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B54, 0x00000FFEU ,0x00000674U), + // .. INP_TYPE = 0x0 + // .. ==> 0XF8000B58[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. DCI_UPDATE_B = 0x0 + // .. ==> 0XF8000B58[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. TERM_EN = 0x0 + // .. ==> 0XF8000B58[4:4] = 0x00000000U + // .. ==> MASK : 0x00000010U VAL : 0x00000000U + // .. DCI_TYPE = 0x0 + // .. ==> 0XF8000B58[6:5] = 0x00000000U + // .. ==> MASK : 0x00000060U VAL : 0x00000000U + // .. IBUF_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B58[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. TERM_DISABLE_MODE = 0x0 + // .. ==> 0XF8000B58[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. OUTPUT_EN = 0x3 + // .. ==> 0XF8000B58[10:9] = 0x00000003U + // .. ==> MASK : 0x00000600U VAL : 0x00000600U + // .. PULLUP_EN = 0x0 + // .. ==> 0XF8000B58[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000B58, 0x00000FFEU ,0x00000600U), + // .. VREF_INT_EN = 0x0 + // .. ==> 0XF8000B6C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. VREF_SEL = 0x0 + // .. ==> 0XF8000B6C[4:1] = 0x00000000U + // .. ==> MASK : 0x0000001EU VAL : 0x00000000U + // .. VREF_EXT_EN = 0x3 + // .. ==> 0XF8000B6C[6:5] = 0x00000003U + // .. ==> MASK : 0x00000060U VAL : 0x00000060U + // .. REFIO_EN = 0x1 + // .. ==> 0XF8000B6C[9:9] = 0x00000001U + // .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. + EMIT_MASKWRITE(0XF8000B6C, 0x0000027FU ,0x00000260U), + // .. .. START: ASSERT RESET + // .. .. RESET = 1 + // .. .. ==> 0XF8000B70[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x00000001U ,0x00000001U), + // .. .. FINISH: ASSERT RESET + // .. .. START: DEASSERT RESET + // .. .. RESET = 0 + // .. .. ==> 0XF8000B70[0:0] = 0x00000000U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x00000001U ,0x00000000U), + // .. .. FINISH: DEASSERT RESET + // .. .. RESET = 0x1 + // .. .. ==> 0XF8000B70[0:0] = 0x00000001U + // .. .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. .. ENABLE = 0x1 + // .. .. ==> 0XF8000B70[1:1] = 0x00000001U + // .. .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. .. NREF_OPT1 = 0x0 + // .. .. ==> 0XF8000B70[7:6] = 0x00000000U + // .. .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. .. NREF_OPT2 = 0x0 + // .. .. ==> 0XF8000B70[10:8] = 0x00000000U + // .. .. ==> MASK : 0x00000700U VAL : 0x00000000U + // .. .. NREF_OPT4 = 0x1 + // .. .. ==> 0XF8000B70[13:11] = 0x00000001U + // .. .. ==> MASK : 0x00003800U VAL : 0x00000800U + // .. .. PREF_OPT2 = 0x0 + // .. .. ==> 0XF8000B70[19:17] = 0x00000000U + // .. .. ==> MASK : 0x000E0000U VAL : 0x00000000U + // .. .. UPDATE_CONTROL = 0x0 + // .. .. ==> 0XF8000B70[20:20] = 0x00000000U + // .. .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. .. + EMIT_MASKWRITE(0XF8000B70, 0x001E3FC3U ,0x00000803U), + // .. FINISH: DDRIOB SETTINGS + // .. START: MIO PROGRAMMING + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000700[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000700[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000700[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000700[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000700[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000700[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000700[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000700[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000700[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000700, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000704[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000704[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000704[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000704[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000704[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000704[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000704[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000704[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000704[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000704, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000708[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000708[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000708[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000708[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000708[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000708[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000708[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000708[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000708[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000708, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800070C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF800070C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800070C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800070C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800070C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800070C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF800070C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800070C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800070C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800070C, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000710[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000710[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000710[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000710[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000710[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000710[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000710[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000710[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000710[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000710, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000714[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000714[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000714[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000714[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000714[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000714[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000714[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000714[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000714[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000714, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000718[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000718[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000718[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000718[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000718[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000718[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000718[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000718[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000718[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000718, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800071C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800071C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800071C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800071C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800071C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF800071C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800071C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800071C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800071C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800071C, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000720[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000720[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000720[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000720[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000720[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000720[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 3 + // .. ==> 0XF8000720[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000720[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000720[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000720, 0x00003FFFU ,0x00000702U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000724[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000724[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000724[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000724[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000724[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000724[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000724[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000724[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000724[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000724, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000728[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000728[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000728[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000728[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000728[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U + // .. Speed = 0 + // .. ==> 0XF8000728[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000728[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 1 + // .. ==> 0XF8000728[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000728[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000728, 0x00003FFFU ,0x00001640U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800072C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800072C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800072C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800072C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF800072C[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U + // .. Speed = 0 + // .. ==> 0XF800072C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800072C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 1 + // .. ==> 0XF800072C[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. DisableRcvr = 0 + // .. ==> 0XF800072C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800072C, 0x00003FFFU ,0x00001640U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000730[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000730[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000730[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000730[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000730[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000730[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000730[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000730[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000730[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000734[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000734[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000734[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000734[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000734[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000734[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000734[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000734[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000734[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000738[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000738[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF8000738[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000738[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000738[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF8000738[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF8000738[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF8000738[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000738[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000738, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800073C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800073C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF800073C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800073C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800073C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF800073C[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 3 + // .. ==> 0XF800073C[11:9] = 0x00000003U + // .. ==> MASK : 0x00000E00U VAL : 0x00000600U + // .. PULLUP = 0 + // .. ==> 0XF800073C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800073C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800073C, 0x00003FFFU ,0x00000600U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000740[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000740[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000740[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000740[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000740[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000740[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000740[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000740[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000740[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000740, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000744[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000744[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000744[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000744[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000744[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000744[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000744[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000744[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000744[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000744, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000748[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000748[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000748[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000748[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000748[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000748[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000748[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000748[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000748[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000748, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800074C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF800074C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800074C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800074C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800074C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800074C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800074C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800074C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF800074C[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF800074C, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000750[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000750[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000750[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000750[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000750[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000750[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000750[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000750[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000750[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000750, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000754[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 1 + // .. ==> 0XF8000754[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000754[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000754[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000754[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000754[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000754[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000754[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 1 + // .. ==> 0XF8000754[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. + EMIT_MASKWRITE(0XF8000754, 0x00003FFFU ,0x00002902U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000758[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000758[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000758[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000758[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000758[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000758[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000758[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000758[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000758[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000758, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800075C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF800075C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800075C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800075C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800075C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800075C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800075C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800075C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800075C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800075C, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000760[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000760[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000760[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000760[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000760[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000760[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000760[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000760[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000760[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000760, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000764[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000764[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000764[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000764[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000764[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000764[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000764[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000764[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000764[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000764, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000768[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF8000768[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF8000768[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF8000768[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000768[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000768[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF8000768[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF8000768[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000768[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000768, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800076C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 1 + // .. ==> 0XF800076C[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. L1_SEL = 0 + // .. ==> 0XF800076C[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF800076C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800076C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800076C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 4 + // .. ==> 0XF800076C[11:9] = 0x00000004U + // .. ==> MASK : 0x00000E00U VAL : 0x00000800U + // .. PULLUP = 0 + // .. ==> 0XF800076C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800076C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800076C, 0x00003FFFU ,0x00000903U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000770[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000770[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000770[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000770[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000770[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000770[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000770[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000770[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000770[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000770, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000774[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF8000774[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000774[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000774[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000774[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000774[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000774[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000774[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000774[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000774, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000778[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000778[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000778[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000778[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000778[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000778[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000778[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000778[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000778[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000778, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF800077C[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF800077C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800077C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800077C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800077C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800077C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800077C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800077C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800077C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800077C, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000780[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000780[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000780[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000780[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000780[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000780[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000780[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000780[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000780[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000780, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000784[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000784[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000784[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000784[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000784[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000784[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000784[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000784[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000784[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000784, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000788[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000788[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000788[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000788[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000788[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000788[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000788[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000788[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000788[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000788, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800078C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800078C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800078C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800078C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800078C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800078C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800078C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800078C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800078C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800078C, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF8000790[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF8000790[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000790[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000790[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000790[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000790[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000790[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000790[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000790[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000790, 0x00003FFFU ,0x00000305U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000794[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000794[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000794[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000794[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000794[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000794[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000794[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000794[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000794[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000794, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF8000798[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF8000798[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF8000798[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF8000798[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF8000798[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF8000798[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF8000798[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF8000798[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF8000798[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000798, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF800079C[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF800079C[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 1 + // .. ==> 0XF800079C[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. L2_SEL = 0 + // .. ==> 0XF800079C[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF800079C[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 1 + // .. ==> 0XF800079C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF800079C[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF800079C[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF800079C[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF800079C, 0x00003FFFU ,0x00000304U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A0[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A0, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A4[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A4, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007A8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007A8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007A8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007A8[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007A8[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007A8[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007A8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007A8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007A8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007A8, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007AC[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007AC[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007AC[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007AC[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007AC[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007AC[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007AC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007AC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007AC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007AC, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007B0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007B0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007B0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007B0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007B0[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007B0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B0, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007B4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007B4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007B4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007B4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 1 + // .. ==> 0XF80007B4[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. IO_Type = 1 + // .. ==> 0XF80007B4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B4, 0x00003FFFU ,0x00000380U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007B8[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007B8[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007B8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007B8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007B8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007B8, 0x00003F01U ,0x00000200U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007BC[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. Speed = 0 + // .. ==> 0XF80007BC[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007BC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007BC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007BC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007BC, 0x00003F01U ,0x00000201U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007C0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007C0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 7 + // .. ==> 0XF80007C0[7:5] = 0x00000007U + // .. ==> MASK : 0x000000E0U VAL : 0x000000E0U + // .. Speed = 0 + // .. ==> 0XF80007C0[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C0, 0x00003FFFU ,0x000002E0U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007C4[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007C4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 7 + // .. ==> 0XF80007C4[7:5] = 0x00000007U + // .. ==> MASK : 0x000000E0U VAL : 0x000000E0U + // .. Speed = 0 + // .. ==> 0XF80007C4[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C4, 0x00003FFFU ,0x000002E1U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007C8[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007C8[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007C8[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007C8[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF80007C8[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007C8[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007C8[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007C8[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007C8[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007C8, 0x00003FFFU ,0x00000201U), + // .. TRI_ENABLE = 1 + // .. ==> 0XF80007CC[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. L0_SEL = 0 + // .. ==> 0XF80007CC[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007CC[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007CC[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 0 + // .. ==> 0XF80007CC[7:5] = 0x00000000U + // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. Speed = 0 + // .. ==> 0XF80007CC[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007CC[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007CC[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007CC[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007CC, 0x00003FFFU ,0x00000201U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007D0[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007D0[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007D0[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007D0[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007D0[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 0 + // .. ==> 0XF80007D0[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007D0[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007D0[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007D0[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007D0, 0x00003FFFU ,0x00000280U), + // .. TRI_ENABLE = 0 + // .. ==> 0XF80007D4[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. L0_SEL = 0 + // .. ==> 0XF80007D4[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. L1_SEL = 0 + // .. ==> 0XF80007D4[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. L2_SEL = 0 + // .. ==> 0XF80007D4[4:3] = 0x00000000U + // .. ==> MASK : 0x00000018U VAL : 0x00000000U + // .. L3_SEL = 4 + // .. ==> 0XF80007D4[7:5] = 0x00000004U + // .. ==> MASK : 0x000000E0U VAL : 0x00000080U + // .. Speed = 0 + // .. ==> 0XF80007D4[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. IO_Type = 1 + // .. ==> 0XF80007D4[11:9] = 0x00000001U + // .. ==> MASK : 0x00000E00U VAL : 0x00000200U + // .. PULLUP = 0 + // .. ==> 0XF80007D4[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. DisableRcvr = 0 + // .. ==> 0XF80007D4[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF80007D4, 0x00003FFFU ,0x00000280U), + // .. SDIO0_CD_SEL = 47 + // .. ==> 0XF8000830[21:16] = 0x0000002FU + // .. ==> MASK : 0x003F0000U VAL : 0x002F0000U + // .. + EMIT_MASKWRITE(0XF8000830, 0x003F0000U ,0x002F0000U), + // .. FINISH: MIO PROGRAMMING + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_peripherals_init_data_3_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: DDR TERM/IBUF_DISABLE_MODE SETTINGS + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B48[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B48[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B48, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B4C[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B4C[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B4C, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B50[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B50[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B50, 0x00000180U ,0x00000180U), + // .. IBUF_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B54[7:7] = 0x00000001U + // .. ==> MASK : 0x00000080U VAL : 0x00000080U + // .. TERM_DISABLE_MODE = 0x1 + // .. ==> 0XF8000B54[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. + EMIT_MASKWRITE(0XF8000B54, 0x00000180U ,0x00000180U), + // .. FINISH: DDR TERM/IBUF_DISABLE_MODE SETTINGS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // .. START: SRAM/NOR SET OPMODE + // .. FINISH: SRAM/NOR SET OPMODE + // .. START: UART REGISTERS + // .. BDIV = 0x5 + // .. ==> 0XE0001034[7:0] = 0x00000005U + // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. + EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000005U), + // .. CD = 0x9 + // .. ==> 0XE0001018[15:0] = 0x00000009U + // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + // .. + EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x00000009U), + // .. STPBRK = 0x0 + // .. ==> 0XE0001000[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. STTBRK = 0x0 + // .. ==> 0XE0001000[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. RSTTO = 0x0 + // .. ==> 0XE0001000[6:6] = 0x00000000U + // .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. TXDIS = 0x0 + // .. ==> 0XE0001000[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. TXEN = 0x1 + // .. ==> 0XE0001000[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. RXDIS = 0x0 + // .. ==> 0XE0001000[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. RXEN = 0x1 + // .. ==> 0XE0001000[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. TXRES = 0x1 + // .. ==> 0XE0001000[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. RXRES = 0x1 + // .. ==> 0XE0001000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XE0001000, 0x000001FFU ,0x00000017U), + // .. CHMODE = 0x0 + // .. ==> 0XE0001004[9:8] = 0x00000000U + // .. ==> MASK : 0x00000300U VAL : 0x00000000U + // .. NBSTOP = 0x0 + // .. ==> 0XE0001004[7:6] = 0x00000000U + // .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. PAR = 0x4 + // .. ==> 0XE0001004[5:3] = 0x00000004U + // .. ==> MASK : 0x00000038U VAL : 0x00000020U + // .. CHRL = 0x0 + // .. ==> 0XE0001004[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. CLKS = 0x0 + // .. ==> 0XE0001004[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XE0001004, 0x000003FFU ,0x00000020U), + // .. BDIV = 0x5 + // .. ==> 0XE0000034[7:0] = 0x00000005U + // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. + EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000005U), + // .. CD = 0x9 + // .. ==> 0XE0000018[15:0] = 0x00000009U + // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + // .. + EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x00000009U), + // .. STPBRK = 0x0 + // .. ==> 0XE0000000[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. STTBRK = 0x0 + // .. ==> 0XE0000000[7:7] = 0x00000000U + // .. ==> MASK : 0x00000080U VAL : 0x00000000U + // .. RSTTO = 0x0 + // .. ==> 0XE0000000[6:6] = 0x00000000U + // .. ==> MASK : 0x00000040U VAL : 0x00000000U + // .. TXDIS = 0x0 + // .. ==> 0XE0000000[5:5] = 0x00000000U + // .. ==> MASK : 0x00000020U VAL : 0x00000000U + // .. TXEN = 0x1 + // .. ==> 0XE0000000[4:4] = 0x00000001U + // .. ==> MASK : 0x00000010U VAL : 0x00000010U + // .. RXDIS = 0x0 + // .. ==> 0XE0000000[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. RXEN = 0x1 + // .. ==> 0XE0000000[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. TXRES = 0x1 + // .. ==> 0XE0000000[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. RXRES = 0x1 + // .. ==> 0XE0000000[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XE0000000, 0x000001FFU ,0x00000017U), + // .. CHMODE = 0x0 + // .. ==> 0XE0000004[9:8] = 0x00000000U + // .. ==> MASK : 0x00000300U VAL : 0x00000000U + // .. NBSTOP = 0x0 + // .. ==> 0XE0000004[7:6] = 0x00000000U + // .. ==> MASK : 0x000000C0U VAL : 0x00000000U + // .. PAR = 0x4 + // .. ==> 0XE0000004[5:3] = 0x00000004U + // .. ==> MASK : 0x00000038U VAL : 0x00000020U + // .. CHRL = 0x0 + // .. ==> 0XE0000004[2:1] = 0x00000000U + // .. ==> MASK : 0x00000006U VAL : 0x00000000U + // .. CLKS = 0x0 + // .. ==> 0XE0000004[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XE0000004, 0x000003FFU ,0x00000020U), + // .. FINISH: UART REGISTERS + // .. START: QSPI REGISTERS + // .. Holdb_dr = 1 + // .. ==> 0XE000D000[19:19] = 0x00000001U + // .. ==> MASK : 0x00080000U VAL : 0x00080000U + // .. + EMIT_MASKWRITE(0XE000D000, 0x00080000U ,0x00080000U), + // .. FINISH: QSPI REGISTERS + // .. START: PL POWER ON RESET REGISTERS + // .. PCFG_POR_CNT_4K = 0 + // .. ==> 0XF8007000[29:29] = 0x00000000U + // .. ==> MASK : 0x20000000U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8007000, 0x20000000U ,0x00000000U), + // .. FINISH: PL POWER ON RESET REGISTERS + // .. START: SMC TIMING CALCULATION REGISTER UPDATE + // .. .. START: NAND SET CYCLE + // .. .. FINISH: NAND SET CYCLE + // .. .. START: OPMODE + // .. .. FINISH: OPMODE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: SRAM/NOR CS0 SET CYCLE + // .. .. FINISH: SRAM/NOR CS0 SET CYCLE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: NOR CS0 BASE ADDRESS + // .. .. FINISH: NOR CS0 BASE ADDRESS + // .. .. START: SRAM/NOR CS1 SET CYCLE + // .. .. FINISH: SRAM/NOR CS1 SET CYCLE + // .. .. START: DIRECT COMMAND + // .. .. FINISH: DIRECT COMMAND + // .. .. START: NOR CS1 BASE ADDRESS + // .. .. FINISH: NOR CS1 BASE ADDRESS + // .. .. START: USB RESET + // .. .. .. START: DIR MODE BANK 0 + // .. .. .. FINISH: DIR MODE BANK 0 + // .. .. .. START: DIR MODE BANK 1 + // .. .. .. DIRECTION_1 = 0x4000 + // .. .. .. ==> 0XE000A244[21:0] = 0x00004000U + // .. .. .. ==> MASK : 0x003FFFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A244, 0x003FFFFFU ,0x00004000U), + // .. .. .. FINISH: DIR MODE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x4000 + // .. .. .. ==> 0XE000A008[15:0] = 0x00004000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF4000U), + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE BANK 0 + // .. .. .. FINISH: OUTPUT ENABLE BANK 0 + // .. .. .. START: OUTPUT ENABLE BANK 1 + // .. .. .. OP_ENABLE_1 = 0x4000 + // .. .. .. ==> 0XE000A248[21:0] = 0x00004000U + // .. .. .. ==> MASK : 0x003FFFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A248, 0x003FFFFFU ,0x00004000U), + // .. .. .. FINISH: OUTPUT ENABLE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x0 + // .. .. .. ==> 0XE000A008[15:0] = 0x00000000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00000000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF0000U), + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. MASK_1_LSW = 0xbfff + // .. .. .. ==> 0XE000A008[31:16] = 0x0000BFFFU + // .. .. .. ==> MASK : 0xFFFF0000U VAL : 0xBFFF0000U + // .. .. .. DATA_1_LSW = 0x4000 + // .. .. .. ==> 0XE000A008[15:0] = 0x00004000U + // .. .. .. ==> MASK : 0x0000FFFFU VAL : 0x00004000U + // .. .. .. + EMIT_MASKWRITE(0XE000A008, 0xFFFFFFFFU ,0xBFFF4000U), + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: USB RESET + // .. .. START: ENET RESET + // .. .. .. START: DIR MODE BANK 0 + // .. .. .. FINISH: DIR MODE BANK 0 + // .. .. .. START: DIR MODE BANK 1 + // .. .. .. FINISH: DIR MODE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE BANK 0 + // .. .. .. FINISH: OUTPUT ENABLE BANK 0 + // .. .. .. START: OUTPUT ENABLE BANK 1 + // .. .. .. FINISH: OUTPUT ENABLE BANK 1 + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: ENET RESET + // .. .. START: I2C RESET + // .. .. .. START: DIR MODE GPIO BANK0 + // .. .. .. FINISH: DIR MODE GPIO BANK0 + // .. .. .. START: DIR MODE GPIO BANK1 + // .. .. .. FINISH: DIR MODE GPIO BANK1 + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. START: OUTPUT ENABLE + // .. .. .. FINISH: OUTPUT ENABLE + // .. .. .. START: OUTPUT ENABLE + // .. .. .. FINISH: OUTPUT ENABLE + // .. .. .. START: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW LOW BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW LOW BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW LOW BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW LOW BANK [53:48] + // .. .. .. START: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. FINISH: MASK_DATA_0_LSW HIGH BANK [15:0] + // .. .. .. START: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. FINISH: MASK_DATA_0_MSW HIGH BANK [31:16] + // .. .. .. START: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. FINISH: MASK_DATA_1_LSW HIGH BANK [47:32] + // .. .. .. START: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. .. FINISH: MASK_DATA_1_MSW HIGH BANK [53:48] + // .. .. FINISH: I2C RESET + // .. FINISH: SMC TIMING CALCULATION REGISTER UPDATE + // FINISH: top + // + EMIT_EXIT(), + + // +}; + +unsigned long ps7_post_config_3_0[] = { + // START: top + // .. START: SLCR SETTINGS + // .. UNLOCK_KEY = 0XDF0D + // .. ==> 0XF8000008[15:0] = 0x0000DF0DU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000DF0DU + // .. + EMIT_MASKWRITE(0XF8000008, 0x0000FFFFU ,0x0000DF0DU), + // .. FINISH: SLCR SETTINGS + // .. START: ENABLING LEVEL SHIFTER + // .. USER_LVL_INP_EN_0 = 1 + // .. ==> 0XF8000900[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. USER_LVL_OUT_EN_0 = 1 + // .. ==> 0XF8000900[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. USER_LVL_INP_EN_1 = 1 + // .. ==> 0XF8000900[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. USER_LVL_OUT_EN_1 = 1 + // .. ==> 0XF8000900[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XF8000900, 0x0000000FU ,0x0000000FU), + // .. FINISH: ENABLING LEVEL SHIFTER + // .. START: FPGA RESETS TO 1 + // .. reserved_3 = 127 + // .. ==> 0XF8000240[31:25] = 0x0000007FU + // .. ==> MASK : 0xFE000000U VAL : 0xFE000000U + // .. reserved_FPGA_ACP_RST = 1 + // .. ==> 0XF8000240[24:24] = 0x00000001U + // .. ==> MASK : 0x01000000U VAL : 0x01000000U + // .. reserved_FPGA_AXDS3_RST = 1 + // .. ==> 0XF8000240[23:23] = 0x00000001U + // .. ==> MASK : 0x00800000U VAL : 0x00800000U + // .. reserved_FPGA_AXDS2_RST = 1 + // .. ==> 0XF8000240[22:22] = 0x00000001U + // .. ==> MASK : 0x00400000U VAL : 0x00400000U + // .. reserved_FPGA_AXDS1_RST = 1 + // .. ==> 0XF8000240[21:21] = 0x00000001U + // .. ==> MASK : 0x00200000U VAL : 0x00200000U + // .. reserved_FPGA_AXDS0_RST = 1 + // .. ==> 0XF8000240[20:20] = 0x00000001U + // .. ==> MASK : 0x00100000U VAL : 0x00100000U + // .. reserved_2 = 3 + // .. ==> 0XF8000240[19:18] = 0x00000003U + // .. ==> MASK : 0x000C0000U VAL : 0x000C0000U + // .. reserved_FSSW1_FPGA_RST = 1 + // .. ==> 0XF8000240[17:17] = 0x00000001U + // .. ==> MASK : 0x00020000U VAL : 0x00020000U + // .. reserved_FSSW0_FPGA_RST = 1 + // .. ==> 0XF8000240[16:16] = 0x00000001U + // .. ==> MASK : 0x00010000U VAL : 0x00010000U + // .. reserved_1 = 15 + // .. ==> 0XF8000240[15:14] = 0x0000000FU + // .. ==> MASK : 0x0000C000U VAL : 0x0000C000U + // .. reserved_FPGA_FMSW1_RST = 1 + // .. ==> 0XF8000240[13:13] = 0x00000001U + // .. ==> MASK : 0x00002000U VAL : 0x00002000U + // .. reserved_FPGA_FMSW0_RST = 1 + // .. ==> 0XF8000240[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U + // .. reserved_FPGA_DMA3_RST = 1 + // .. ==> 0XF8000240[11:11] = 0x00000001U + // .. ==> MASK : 0x00000800U VAL : 0x00000800U + // .. reserved_FPGA_DMA2_RST = 1 + // .. ==> 0XF8000240[10:10] = 0x00000001U + // .. ==> MASK : 0x00000400U VAL : 0x00000400U + // .. reserved_FPGA_DMA1_RST = 1 + // .. ==> 0XF8000240[9:9] = 0x00000001U + // .. ==> MASK : 0x00000200U VAL : 0x00000200U + // .. reserved_FPGA_DMA0_RST = 1 + // .. ==> 0XF8000240[8:8] = 0x00000001U + // .. ==> MASK : 0x00000100U VAL : 0x00000100U + // .. reserved = 15 + // .. ==> 0XF8000240[7:4] = 0x0000000FU + // .. ==> MASK : 0x000000F0U VAL : 0x000000F0U + // .. FPGA3_OUT_RST = 1 + // .. ==> 0XF8000240[3:3] = 0x00000001U + // .. ==> MASK : 0x00000008U VAL : 0x00000008U + // .. FPGA2_OUT_RST = 1 + // .. ==> 0XF8000240[2:2] = 0x00000001U + // .. ==> MASK : 0x00000004U VAL : 0x00000004U + // .. FPGA1_OUT_RST = 1 + // .. ==> 0XF8000240[1:1] = 0x00000001U + // .. ==> MASK : 0x00000002U VAL : 0x00000002U + // .. FPGA0_OUT_RST = 1 + // .. ==> 0XF8000240[0:0] = 0x00000001U + // .. ==> MASK : 0x00000001U VAL : 0x00000001U + // .. + EMIT_MASKWRITE(0XF8000240, 0xFFFFFFFFU ,0xFFFFFFFFU), + // .. FINISH: FPGA RESETS TO 1 + // .. START: FPGA RESETS TO 0 + // .. reserved_3 = 0 + // .. ==> 0XF8000240[31:25] = 0x00000000U + // .. ==> MASK : 0xFE000000U VAL : 0x00000000U + // .. reserved_FPGA_ACP_RST = 0 + // .. ==> 0XF8000240[24:24] = 0x00000000U + // .. ==> MASK : 0x01000000U VAL : 0x00000000U + // .. reserved_FPGA_AXDS3_RST = 0 + // .. ==> 0XF8000240[23:23] = 0x00000000U + // .. ==> MASK : 0x00800000U VAL : 0x00000000U + // .. reserved_FPGA_AXDS2_RST = 0 + // .. ==> 0XF8000240[22:22] = 0x00000000U + // .. ==> MASK : 0x00400000U VAL : 0x00000000U + // .. reserved_FPGA_AXDS1_RST = 0 + // .. ==> 0XF8000240[21:21] = 0x00000000U + // .. ==> MASK : 0x00200000U VAL : 0x00000000U + // .. reserved_FPGA_AXDS0_RST = 0 + // .. ==> 0XF8000240[20:20] = 0x00000000U + // .. ==> MASK : 0x00100000U VAL : 0x00000000U + // .. reserved_2 = 0 + // .. ==> 0XF8000240[19:18] = 0x00000000U + // .. ==> MASK : 0x000C0000U VAL : 0x00000000U + // .. reserved_FSSW1_FPGA_RST = 0 + // .. ==> 0XF8000240[17:17] = 0x00000000U + // .. ==> MASK : 0x00020000U VAL : 0x00000000U + // .. reserved_FSSW0_FPGA_RST = 0 + // .. ==> 0XF8000240[16:16] = 0x00000000U + // .. ==> MASK : 0x00010000U VAL : 0x00000000U + // .. reserved_1 = 0 + // .. ==> 0XF8000240[15:14] = 0x00000000U + // .. ==> MASK : 0x0000C000U VAL : 0x00000000U + // .. reserved_FPGA_FMSW1_RST = 0 + // .. ==> 0XF8000240[13:13] = 0x00000000U + // .. ==> MASK : 0x00002000U VAL : 0x00000000U + // .. reserved_FPGA_FMSW0_RST = 0 + // .. ==> 0XF8000240[12:12] = 0x00000000U + // .. ==> MASK : 0x00001000U VAL : 0x00000000U + // .. reserved_FPGA_DMA3_RST = 0 + // .. ==> 0XF8000240[11:11] = 0x00000000U + // .. ==> MASK : 0x00000800U VAL : 0x00000000U + // .. reserved_FPGA_DMA2_RST = 0 + // .. ==> 0XF8000240[10:10] = 0x00000000U + // .. ==> MASK : 0x00000400U VAL : 0x00000000U + // .. reserved_FPGA_DMA1_RST = 0 + // .. ==> 0XF8000240[9:9] = 0x00000000U + // .. ==> MASK : 0x00000200U VAL : 0x00000000U + // .. reserved_FPGA_DMA0_RST = 0 + // .. ==> 0XF8000240[8:8] = 0x00000000U + // .. ==> MASK : 0x00000100U VAL : 0x00000000U + // .. reserved = 0 + // .. ==> 0XF8000240[7:4] = 0x00000000U + // .. ==> MASK : 0x000000F0U VAL : 0x00000000U + // .. FPGA3_OUT_RST = 0 + // .. ==> 0XF8000240[3:3] = 0x00000000U + // .. ==> MASK : 0x00000008U VAL : 0x00000000U + // .. FPGA2_OUT_RST = 0 + // .. ==> 0XF8000240[2:2] = 0x00000000U + // .. ==> MASK : 0x00000004U VAL : 0x00000000U + // .. FPGA1_OUT_RST = 0 + // .. ==> 0XF8000240[1:1] = 0x00000000U + // .. ==> MASK : 0x00000002U VAL : 0x00000000U + // .. FPGA0_OUT_RST = 0 + // .. ==> 0XF8000240[0:0] = 0x00000000U + // .. ==> MASK : 0x00000001U VAL : 0x00000000U + // .. + EMIT_MASKWRITE(0XF8000240, 0xFFFFFFFFU ,0x00000000U), + // .. FINISH: FPGA RESETS TO 0 + // .. START: AFI REGISTERS + // .. .. START: AFI0 REGISTERS + // .. .. FINISH: AFI0 REGISTERS + // .. .. START: AFI1 REGISTERS + // .. .. FINISH: AFI1 REGISTERS + // .. .. START: AFI2 REGISTERS + // .. .. FINISH: AFI2 REGISTERS + // .. .. START: AFI3 REGISTERS + // .. .. FINISH: AFI3 REGISTERS + // .. FINISH: AFI REGISTERS + // .. START: LOCK IT BACK + // .. LOCK_KEY = 0X767B + // .. ==> 0XF8000004[15:0] = 0x0000767BU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000767BU + // .. + EMIT_MASKWRITE(0XF8000004, 0x0000FFFFU ,0x0000767BU), + // .. FINISH: LOCK IT BACK + // FINISH: top + // + EMIT_EXIT(), + + // +}; + + +#include "xil_io.h" +#define PS7_MASK_POLL_TIME 100000000 + +char* +getPS7MessageInfo(unsigned key) { + + char* err_msg = ""; + switch (key) { + case PS7_INIT_SUCCESS: err_msg = "PS7 initialization successful"; break; + case PS7_INIT_CORRUPT: err_msg = "PS7 init Data Corrupted"; break; + case PS7_INIT_TIMEOUT: err_msg = "PS7 init mask poll timeout"; break; + case PS7_POLL_FAILED_DDR_INIT: err_msg = "Mask Poll failed for DDR Init"; break; + case PS7_POLL_FAILED_DMA: err_msg = "Mask Poll failed for PLL Init"; break; + case PS7_POLL_FAILED_PLL: err_msg = "Mask Poll failed for DMA done bit"; break; + default: err_msg = "Undefined error status"; break; + } + + return err_msg; +} + +unsigned long +ps7GetSiliconVersion () { + // Read PS version from MCTRL register [31:28] + unsigned long mask = 0xF0000000; + unsigned long *addr = (unsigned long*) 0XF8007080; + unsigned long ps_version = (*addr & mask) >> 28; + return ps_version; +} + +void mask_write (unsigned long add , unsigned long mask, unsigned long val ) { + unsigned long *addr = (unsigned long*) add; + *addr = ( val & mask ) | ( *addr & ~mask); + //xil_printf("MaskWrite : 0x%x--> 0x%x \n \r" ,add, *addr); +} + + +int mask_poll(unsigned long add , unsigned long mask ) { + unsigned long *addr = (unsigned long*) add; + int i = 0; + while (!(*addr & mask)) { + if (i == PS7_MASK_POLL_TIME) { + return -1; + } + i++; + } + return 1; + //xil_printf("MaskPoll : 0x%x --> 0x%x \n \r" , add, *addr); +} + +unsigned long mask_read(unsigned long add , unsigned long mask ) { + unsigned long *addr = (unsigned long*) add; + unsigned long val = (*addr & mask); + //xil_printf("MaskRead : 0x%x --> 0x%x \n \r" , add, val); + return val; +} + + + +int +ps7_config(unsigned long * ps7_config_init) +{ + unsigned long *ptr = ps7_config_init; + + unsigned long opcode; // current instruction .. + unsigned long args[16]; // no opcode has so many args ... + int numargs; // number of arguments of this instruction + int j; // general purpose index + + volatile unsigned long *addr; // some variable to make code readable + unsigned long val,mask; // some variable to make code readable + + int finish = -1 ; // loop while this is negative ! + int i = 0; // Timeout variable + + while( finish < 0 ) { + numargs = ptr[0] & 0xF; + opcode = ptr[0] >> 4; + + for( j = 0 ; j < numargs ; j ++ ) + args[j] = ptr[j+1]; + ptr += numargs + 1; + + + switch ( opcode ) { + + case OPCODE_EXIT: + finish = PS7_INIT_SUCCESS; + break; + + case OPCODE_CLEAR: + addr = (unsigned long*) args[0]; + *addr = 0; + break; + + case OPCODE_WRITE: + addr = (unsigned long*) args[0]; + val = args[1]; + *addr = val; + break; + + case OPCODE_MASKWRITE: + addr = (unsigned long*) args[0]; + mask = args[1]; + val = args[2]; + *addr = ( val & mask ) | ( *addr & ~mask); + break; + + case OPCODE_MASKPOLL: + addr = (unsigned long*) args[0]; + mask = args[1]; + i = 0; + while (!(*addr & mask)) { + if (i == PS7_MASK_POLL_TIME) { + finish = PS7_INIT_TIMEOUT; + break; + } + i++; + } + break; + default: + finish = PS7_INIT_CORRUPT; + break; + } + } + return finish; +} + +unsigned long *ps7_mio_init_data = ps7_mio_init_data_3_0; +unsigned long *ps7_pll_init_data = ps7_pll_init_data_3_0; +unsigned long *ps7_clock_init_data = ps7_clock_init_data_3_0; +unsigned long *ps7_ddr_init_data = ps7_ddr_init_data_3_0; +unsigned long *ps7_peripherals_init_data = ps7_peripherals_init_data_3_0; + +int +ps7_post_config() +{ + // Get the PS_VERSION on run time + unsigned long si_ver = ps7GetSiliconVersion (); + int ret = -1; + if (si_ver == PCW_SILICON_VERSION_1) { + ret = ps7_config (ps7_post_config_1_0); + if (ret != PS7_INIT_SUCCESS) return ret; + } else if (si_ver == PCW_SILICON_VERSION_2) { + ret = ps7_config (ps7_post_config_2_0); + if (ret != PS7_INIT_SUCCESS) return ret; + } else { + ret = ps7_config (ps7_post_config_3_0); + if (ret != PS7_INIT_SUCCESS) return ret; + } + return PS7_INIT_SUCCESS; +} + +int +ps7_init() +{ + // Get the PS_VERSION on run time + unsigned long si_ver = ps7GetSiliconVersion (); + //int pcw_ver = 0; + + if (si_ver == PCW_SILICON_VERSION_1) { + ps7_mio_init_data = ps7_mio_init_data_1_0; + ps7_pll_init_data = ps7_pll_init_data_1_0; + ps7_clock_init_data = ps7_clock_init_data_1_0; + ps7_ddr_init_data = ps7_ddr_init_data_1_0; + ps7_peripherals_init_data = ps7_peripherals_init_data_1_0; + //pcw_ver = 1; + + } else if (si_ver == PCW_SILICON_VERSION_2) { + ps7_mio_init_data = ps7_mio_init_data_2_0; + ps7_pll_init_data = ps7_pll_init_data_2_0; + ps7_clock_init_data = ps7_clock_init_data_2_0; + ps7_ddr_init_data = ps7_ddr_init_data_2_0; + ps7_peripherals_init_data = ps7_peripherals_init_data_2_0; + //pcw_ver = 2; + + } else { + ps7_mio_init_data = ps7_mio_init_data_3_0; + ps7_pll_init_data = ps7_pll_init_data_3_0; + ps7_clock_init_data = ps7_clock_init_data_3_0; + ps7_ddr_init_data = ps7_ddr_init_data_3_0; + ps7_peripherals_init_data = ps7_peripherals_init_data_3_0; + //pcw_ver = 3; + } + + // MIO init + int ret = ps7_config (ps7_mio_init_data); + if (ret != PS7_INIT_SUCCESS) return ret; + + // PLL init + ret = ps7_config (ps7_pll_init_data); + if (ret != PS7_INIT_SUCCESS) return ret; + + // Clock init + ret = ps7_config (ps7_clock_init_data); + if (ret != PS7_INIT_SUCCESS) return ret; + + // DDR init + ret = ps7_config (ps7_ddr_init_data); + if (ret != PS7_INIT_SUCCESS) return ret; + + + // Peripherals init + ret = ps7_config (ps7_peripherals_init_data); + if (ret != PS7_INIT_SUCCESS) return ret; + //xil_printf ("\n PCW Silicon Version : %d.0", pcw_ver); + return PS7_INIT_SUCCESS; +} + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.h b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.h new file mode 100644 index 0000000000000000000000000000000000000000..d63682e6a8d848399e05e9962eb7473e84e4a954 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.h @@ -0,0 +1,139 @@ + +/****************************************************************************** +* +* (c) Copyright 2010-2012 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +******************************************************************************/ +/****************************************************************************/ +/** +* +* @file ps7_init.h +* +* This file can be included in FSBL code +* to get prototype of ps7_init() function +* and error codes +* +*****************************************************************************/ + +#ifdef __cplusplus +extern "C" { +#endif + + +//typedef unsigned int u32; + + +/** do we need to make this name more unique ? **/ +//extern u32 ps7_init_data[]; +extern unsigned long * ps7_ddr_init_data; +extern unsigned long * ps7_mio_init_data; +extern unsigned long * ps7_pll_init_data; +extern unsigned long * ps7_clock_init_data; +extern unsigned long * ps7_peripherals_init_data; + + + +#define OPCODE_EXIT 0U +#define OPCODE_CLEAR 1U +#define OPCODE_WRITE 2U +#define OPCODE_MASKWRITE 3U +#define OPCODE_MASKPOLL 4U +#define NEW_PS7_ERR_CODE 1 + + +/* Encode number of arguments in last nibble */ +#define EMIT_EXIT() ( (OPCODE_EXIT << 4 ) | 0 ) +#define EMIT_CLEAR(addr) ( (OPCODE_CLEAR << 4 ) | 1 ) , addr +#define EMIT_WRITE(addr,val) ( (OPCODE_WRITE << 4 ) | 2 ) , addr, val +#define EMIT_MASKWRITE(addr,mask,val) ( (OPCODE_MASKWRITE << 4 ) | 3 ) , addr, mask, val +#define EMIT_MASKPOLL(addr,mask) ( (OPCODE_MASKPOLL << 4 ) | 2 ) , addr, mask + + + +/* Returns codes of PS7_Init */ +#define PS7_INIT_SUCCESS (0) // 0 is success in good old C +#define PS7_INIT_CORRUPT (1) // 1 the data is corrupted, and slcr reg are in corrupted state now +#define PS7_INIT_TIMEOUT (2) // 2 when a poll operation timed out +#define PS7_POLL_FAILED_DDR_INIT (3) // 3 when a poll operation timed out for ddr init +#define PS7_POLL_FAILED_DMA (4) // 4 when a poll operation timed out for dma done bit +#define PS7_POLL_FAILED_PLL (5) // 5 when a poll operation timed out for pll sequence init + + +/* Silicon Versions */ +#define PCW_SILICON_VERSION_1 0 +#define PCW_SILICON_VERSION_2 1 +#define PCW_SILICON_VERSION_3 2 + +/* This flag to be used by FSBL to check whether ps7_post_config() proc exixts */ +#define PS7_POST_CONFIG + +/* Freq of all peripherals */ + +#define APU_FREQ 650000000 +#define DDR_FREQ 525000000 +#define DCI_FREQ 10159000 +#define QSPI_FREQ 200000000 +#define SMC_FREQ 100000000 +#define ENET0_FREQ 125000000 +#define ENET1_FREQ 125000000 +#define USB0_FREQ 60000000 +#define USB1_FREQ 60000000 +#define SDIO_FREQ 50000000 +#define UART_FREQ 50000000 +#define SPI_FREQ 166666666 +#define I2C_FREQ 108333336 +#define WDT_FREQ 133333333 +#define TTC_FREQ 50000000 +#define CAN_FREQ 100000000 +#define PCAP_FREQ 200000000 +#define TPIU_FREQ 0 +#define FPGA0_FREQ 100000000 +#define FPGA1_FREQ 175000000 +#define FPGA2_FREQ 12288000 +#define FPGA3_FREQ 100000000 +#define C_CPU_REF_CLK_FREQ_HZ 50000000 + + +int ps7_config( unsigned long*); +int ps7_init(); +int ps7_post_config(); +char* getPS7MessageInfo(unsigned key); + +#ifdef __cplusplus +} +#endif diff --git a/quad/xsdk_workspace/zybo_fsbl/src/qspi.c b/quad/xsdk_workspace/zybo_fsbl/src/qspi.c new file mode 100644 index 0000000000000000000000000000000000000000..6e1c15f713b79b95a46e533bfa4c05109415e5db --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/qspi.c @@ -0,0 +1,724 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file qspi.c +* +* Contains code for the QSPI FLASH functionality. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 01/10/10 Initial release +* 3.00a mb 25/06/12 InitQspi, data is read first and required config bits +* are set +* 4.00a sg 02/28/13 Cleanup +* Removed LPBK_DLY_ADJ register setting code as we use +* divisor 8 +* 5.00a sgd 05/17/13 Added Flash Size > 128Mbit support +* Dual Stack support +* Fix for CR:721674 - FSBL- Failed to boot from Dual +* stacked QSPI +* 6.00a kc 08/30/13 Fix for CR#722979 - Provide customer-friendly +* changelogs in FSBL +* Fix for CR#739711 - FSBL not able to read Large QSPI +* (512M) in IO Mode +* </pre> +* +* @note +* +******************************************************************************/ + +/***************************** Include Files *********************************/ + +#include "qspi.h" +#include "image_mover.h" + +#ifdef XPAR_PS7_QSPI_LINEAR_0_S_AXI_BASEADDR +#include "xqspips_hw.h" +#include "xqspips.h" + +/************************** Constant Definitions *****************************/ + +/* + * The following constants map to the XPAR parameters created in the + * xparameters.h file. They are defined here such that a user can easily + * change all the needed parameters in one place. + */ +#define QSPI_DEVICE_ID XPAR_XQSPIPS_0_DEVICE_ID + +/* + * The following constants define the commands which may be sent to the FLASH + * device. + */ +#define QUAD_READ_CMD 0x6B +#define READ_ID_CMD 0x9F + +#define WRITE_ENABLE_CMD 0x06 +#define BANK_REG_RD 0x16 +#define BANK_REG_WR 0x17 +/* Bank register is called Extended Address Reg in Micron */ +#define EXTADD_REG_RD 0xC8 +#define EXTADD_REG_WR 0xC5 + +#define COMMAND_OFFSET 0 /* FLASH instruction */ +#define ADDRESS_1_OFFSET 1 /* MSB byte of address to read or write */ +#define ADDRESS_2_OFFSET 2 /* Middle byte of address to read or write */ +#define ADDRESS_3_OFFSET 3 /* LSB byte of address to read or write */ +#define DATA_OFFSET 4 /* Start of Data for Read/Write */ +#define DUMMY_OFFSET 4 /* Dummy byte offset for fast, dual and quad + reads */ +#define DUMMY_SIZE 1 /* Number of dummy bytes for fast, dual and + quad reads */ +#define RD_ID_SIZE 4 /* Read ID command + 3 bytes ID response */ +#define BANK_SEL_SIZE 2 /* BRWR or EARWR command + 1 byte bank value */ +#define WRITE_ENABLE_CMD_SIZE 1 /* WE command */ +/* + * The following constants specify the extra bytes which are sent to the + * FLASH on the QSPI interface, that are not data, but control information + * which includes the command and address + */ +#define OVERHEAD_SIZE 4 + +/* + * The following constants specify the max amount of data and the size of the + * the buffer required to hold the data and overhead to transfer the data to + * and from the FLASH. + */ +#define DATA_SIZE 4096 + +/* + * The following defines are for dual flash interface. + */ +#define LQSPI_CR_FAST_QUAD_READ 0x0000006B /* Fast Quad Read output */ +#define LQSPI_CR_1_DUMMY_BYTE 0x00000100 /* 1 Dummy Byte between + address and return data */ + +#define SINGLE_QSPI_CONFIG_QUAD_READ (XQSPIPS_LQSPI_CR_LINEAR_MASK | \ + LQSPI_CR_1_DUMMY_BYTE | \ + LQSPI_CR_FAST_QUAD_READ) + +#define DUAL_QSPI_CONFIG_QUAD_READ (XQSPIPS_LQSPI_CR_LINEAR_MASK | \ + XQSPIPS_LQSPI_CR_TWO_MEM_MASK | \ + XQSPIPS_LQSPI_CR_SEP_BUS_MASK | \ + LQSPI_CR_1_DUMMY_BYTE | \ + LQSPI_CR_FAST_QUAD_READ) + +#define DUAL_STACK_CONFIG_READ (XQSPIPS_LQSPI_CR_TWO_MEM_MASK | \ + LQSPI_CR_1_DUMMY_BYTE | \ + LQSPI_CR_FAST_QUAD_READ) + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ + +/************************** Variable Definitions *****************************/ + +XQspiPs QspiInstance; +XQspiPs *QspiInstancePtr; +u32 QspiFlashSize; +u32 QspiFlashMake; +extern u32 FlashReadBaseAddress; +extern u8 LinearBootDeviceFlag; + +/* + * The following variables are used to read and write to the eeprom and they + * are global to avoid having large buffers on the stack + */ +u8 ReadBuffer[DATA_SIZE + DATA_OFFSET + DUMMY_SIZE]; +u8 WriteBuffer[DATA_OFFSET + DUMMY_SIZE]; + +/******************************************************************************/ +/** +* +* This function initializes the controller for the QSPI interface. +* +* @param None +* +* @return None +* +* @note None +* +****************************************************************************/ +u32 InitQspi(void) +{ + XQspiPs_Config *QspiConfig; + int Status; + + QspiInstancePtr = &QspiInstance; + + /* + * Set up the base address for access + */ + FlashReadBaseAddress = XPS_QSPI_LINEAR_BASEADDR; + + /* + * Initialize the QSPI driver so that it's ready to use + */ + QspiConfig = XQspiPs_LookupConfig(QSPI_DEVICE_ID); + if (NULL == QspiConfig) { + return XST_FAILURE; + } + + Status = XQspiPs_CfgInitialize(QspiInstancePtr, QspiConfig, + QspiConfig->BaseAddress); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + + /* + * Set Manual Chip select options and drive HOLD_B pin high. + */ + XQspiPs_SetOptions(QspiInstancePtr, XQSPIPS_FORCE_SSELECT_OPTION | + XQSPIPS_HOLD_B_DRIVE_OPTION); + + /* + * Set the prescaler for QSPI clock + */ + XQspiPs_SetClkPrescaler(QspiInstancePtr, XQSPIPS_CLK_PRESCALE_8); + + /* + * Assert the FLASH chip select. + */ + XQspiPs_SetSlaveSelect(QspiInstancePtr); + + /* + * Read Flash ID and extract Manufacture and Size information + */ + Status = FlashReadID(); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + + if (XPAR_PS7_QSPI_0_QSPI_MODE == SINGLE_FLASH_CONNECTION) { + + fsbl_printf(DEBUG_INFO,"QSPI is in single flash connection\r\n"); + /* + * For Flash size <128Mbit controller configured in linear mode + */ + if (QspiFlashSize <= FLASH_SIZE_16MB) { + LinearBootDeviceFlag = 1; + + /* + * Enable linear mode + */ + XQspiPs_SetOptions(QspiInstancePtr, XQSPIPS_LQSPI_MODE_OPTION | + XQSPIPS_HOLD_B_DRIVE_OPTION); + + /* + * Single linear read + */ + XQspiPs_SetLqspiConfigReg(QspiInstancePtr, SINGLE_QSPI_CONFIG_QUAD_READ); + + /* + * Enable the controller + */ + XQspiPs_Enable(QspiInstancePtr); + } + } + + if (XPAR_PS7_QSPI_0_QSPI_MODE == DUAL_PARALLEL_CONNECTION) { + + fsbl_printf(DEBUG_INFO,"QSPI is in Dual Parallel connection\r\n"); + /* + * For Single Flash size <128Mbit controller configured in linear mode + */ + if (QspiFlashSize <= FLASH_SIZE_16MB) { + /* + * Setting linear access flag + */ + LinearBootDeviceFlag = 1; + + /* + * Enable linear mode + */ + XQspiPs_SetOptions(QspiInstancePtr, XQSPIPS_LQSPI_MODE_OPTION | + XQSPIPS_HOLD_B_DRIVE_OPTION); + + /* + * Dual linear read + */ + XQspiPs_SetLqspiConfigReg(QspiInstancePtr, DUAL_QSPI_CONFIG_QUAD_READ); + + /* + * Enable the controller + */ + XQspiPs_Enable(QspiInstancePtr); + } + + /* + * Total flash size is two time of single flash size + */ + QspiFlashSize = 2 * QspiFlashSize; + } + + /* + * It is expected to same flash size for both chip selection + */ + if (XPAR_PS7_QSPI_0_QSPI_MODE == DUAL_STACK_CONNECTION) { + + fsbl_printf(DEBUG_INFO,"QSPI is in Dual Stack connection\r\n"); + + QspiFlashSize = 2 * QspiFlashSize; + + /* + * Enable two flash memories on separate buses + */ + XQspiPs_SetLqspiConfigReg(QspiInstancePtr, DUAL_STACK_CONFIG_READ); + } + + return XST_SUCCESS; +} + +/****************************************************************************** +* +* This function reads serial FLASH ID connected to the SPI interface. +* It then deduces the make and size of the flash and obtains the +* connection mode to point to corresponding parameters in the flash +* configuration table. The flash driver will function based on this and +* it presently supports Micron and Spansion - 128, 256 and 512Mbit and +* Winbond 128Mbit +* +* @param none +* +* @return XST_SUCCESS if read id, otherwise XST_FAILURE. +* +* @note None. +* +******************************************************************************/ +u32 FlashReadID(void) +{ + u32 Status; + + /* + * Read ID in Auto mode. + */ + WriteBuffer[COMMAND_OFFSET] = READ_ID_CMD; + WriteBuffer[ADDRESS_1_OFFSET] = 0x00; /* 3 dummy bytes */ + WriteBuffer[ADDRESS_2_OFFSET] = 0x00; + WriteBuffer[ADDRESS_3_OFFSET] = 0x00; + + Status = XQspiPs_PolledTransfer(QspiInstancePtr, WriteBuffer, ReadBuffer, + RD_ID_SIZE); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + + fsbl_printf(DEBUG_INFO,"Single Flash Information\r\n"); + + fsbl_printf(DEBUG_INFO,"FlashID=0x%x 0x%x 0x%x\r\n", ReadBuffer[1], + ReadBuffer[2], + ReadBuffer[3]); + + /* + * Deduce flash make + */ + if (ReadBuffer[1] == MICRON_ID) { + QspiFlashMake = MICRON_ID; + fsbl_printf(DEBUG_INFO, "MICRON "); + } else if(ReadBuffer[1] == SPANSION_ID) { + QspiFlashMake = SPANSION_ID; + fsbl_printf(DEBUG_INFO, "SPANSION "); + } else if(ReadBuffer[1] == WINBOND_ID) { + QspiFlashMake = WINBOND_ID; + fsbl_printf(DEBUG_INFO, "WINBOND "); + } + + /* + * Deduce flash Size + */ + if (ReadBuffer[3] == FLASH_SIZE_ID_128M) { + QspiFlashSize = FLASH_SIZE_128M; + fsbl_printf(DEBUG_INFO, "128M Bits\r\n"); + } else if (ReadBuffer[3] == FLASH_SIZE_ID_256M) { + QspiFlashSize = FLASH_SIZE_256M; + fsbl_printf(DEBUG_INFO, "256M Bits\r\n"); + } else if (ReadBuffer[3] == FLASH_SIZE_ID_512M) { + QspiFlashSize = FLASH_SIZE_512M; + fsbl_printf(DEBUG_INFO, "512M Bits\r\n"); + } else if (ReadBuffer[3] == FLASH_SIZE_ID_1G) { + QspiFlashSize = FLASH_SIZE_1G; + fsbl_printf(DEBUG_INFO, "1G Bits\r\n"); + } + + return XST_SUCCESS; +} + + +/****************************************************************************** +* +* This function reads from the serial FLASH connected to the +* QSPI interface. +* +* @param Address contains the address to read data from in the FLASH. +* @param ByteCount contains the number of bytes to read. +* +* @return None. +* +* @note None. +* +******************************************************************************/ +void FlashRead(u32 Address, u32 ByteCount) +{ + /* + * Setup the write command with the specified address and data for the + * FLASH + */ + WriteBuffer[COMMAND_OFFSET] = QUAD_READ_CMD; + WriteBuffer[ADDRESS_1_OFFSET] = (u8)((Address & 0xFF0000) >> 16); + WriteBuffer[ADDRESS_2_OFFSET] = (u8)((Address & 0xFF00) >> 8); + WriteBuffer[ADDRESS_3_OFFSET] = (u8)(Address & 0xFF); + + ByteCount += DUMMY_SIZE; + + /* + * Send the read command to the FLASH to read the specified number + * of bytes from the FLASH, send the read command and address and + * receive the specified number of bytes of data in the data buffer + */ + XQspiPs_PolledTransfer(QspiInstancePtr, WriteBuffer, ReadBuffer, + ByteCount + OVERHEAD_SIZE); +} + +/******************************************************************************/ +/** +* +* This function provides the QSPI FLASH interface for the Simplified header +* functionality. +* +* @param SourceAddress is address in FLASH data space +* @param DestinationAddress is address in DDR data space +* @param LengthBytes is the length of the data in Bytes +* +* @return +* - XST_SUCCESS if the write completes correctly +* - XST_FAILURE if the write fails to completes correctly +* +* @note none. +* +****************************************************************************/ +u32 QspiAccess( u32 SourceAddress, u32 DestinationAddress, u32 LengthBytes) +{ + u8 *BufferPtr; + u32 Length = 0; + u32 BankSel = 0; + u32 LqspiCrReg; + u32 Status; + u8 BankSwitchFlag = 1; + + /* + * Linear access check + */ + if (LinearBootDeviceFlag == 1) { + /* + * Check for non-word tail, add bytes to cover the end + */ + if ((LengthBytes%4) != 0){ + LengthBytes += (4 - (LengthBytes & 0x00000003)); + } + + memcpy((void*)DestinationAddress, + (const void*)(SourceAddress + FlashReadBaseAddress), + (size_t)LengthBytes); + } else { + /* + * Non Linear access + */ + BufferPtr = (u8*)DestinationAddress; + + /* + * Dual parallel connection actual flash is half + */ + if (XPAR_PS7_QSPI_0_QSPI_MODE == DUAL_PARALLEL_CONNECTION) { + SourceAddress = SourceAddress/2; + } + + while(LengthBytes > 0) { + /* + * Local of DATA_SIZE size used for read/write buffer + */ + if(LengthBytes > DATA_SIZE) { + Length = DATA_SIZE; + } else { + Length = LengthBytes; + } + + /* + * Dual stack connection + */ + if (XPAR_PS7_QSPI_0_QSPI_MODE == DUAL_STACK_CONNECTION) { + /* + * Get the current LQSPI configuration value + */ + LqspiCrReg = XQspiPs_GetLqspiConfigReg(QspiInstancePtr); + + /* + * Select lower or upper Flash based on sector address + */ + if (SourceAddress >= (QspiFlashSize/2)) { + /* + * Set selection to U_PAGE + */ + XQspiPs_SetLqspiConfigReg(QspiInstancePtr, + LqspiCrReg | XQSPIPS_LQSPI_CR_U_PAGE_MASK); + + /* + * Subtract first flash size when accessing second flash + */ + SourceAddress = SourceAddress - (QspiFlashSize/2); + + fsbl_printf(DEBUG_INFO, "stacked - upper CS \n\r"); + + /* + * Assert the FLASH chip select. + */ + XQspiPs_SetSlaveSelect(QspiInstancePtr); + } + } + + /* + * Select bank + */ + if ((SourceAddress >= FLASH_SIZE_16MB) && (BankSwitchFlag == 1)) { + BankSel = SourceAddress/FLASH_SIZE_16MB; + + fsbl_printf(DEBUG_INFO, "Bank Selection %d\n\r", BankSel); + + Status = SendBankSelect(BankSel); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO, "Bank Selection Failed\n\r"); + return XST_FAILURE; + } + + BankSwitchFlag = 0; + } + + /* + * If data to be read spans beyond the current bank, then + * calculate length in current bank else no change in length + */ + if (XPAR_PS7_QSPI_0_QSPI_MODE == DUAL_PARALLEL_CONNECTION) { + /* + * In dual parallel mode, check should be for half + * the length. + */ + if((SourceAddress & BANKMASK) != ((SourceAddress + (Length/2)) & BANKMASK)) + { + Length = (SourceAddress & BANKMASK) + FLASH_SIZE_16MB - SourceAddress; + /* + * Above length calculated is for single flash + * Length should be doubled since dual parallel + */ + Length = Length * 2; + BankSwitchFlag = 1; + } + } else { + if((SourceAddress & BANKMASK) != ((SourceAddress + Length) & BANKMASK)) + { + Length = (SourceAddress & BANKMASK) + FLASH_SIZE_16MB - SourceAddress; + BankSwitchFlag = 1; + } + } + + /* + * Copying the image to local buffer + */ + FlashRead(SourceAddress, Length); + + /* + * Moving the data from local buffer to DDR destination address + */ + memcpy(BufferPtr, &ReadBuffer[DATA_OFFSET + DUMMY_SIZE], Length); + + /* + * Updated the variables + */ + LengthBytes -= Length; + + /* + * For Dual parallel connection address increment should be half + */ + if (XPAR_PS7_QSPI_0_QSPI_MODE == DUAL_PARALLEL_CONNECTION) { + SourceAddress += Length/2; + } else { + SourceAddress += Length; + } + + BufferPtr = (u8*)((u32)BufferPtr + Length); + } + + /* + * Reset Bank selection to zero + */ + Status = SendBankSelect(0); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO, "Bank Selection Reset Failed\n\r"); + return XST_FAILURE; + } + + if (XPAR_PS7_QSPI_0_QSPI_MODE == DUAL_STACK_CONNECTION) { + + /* + * Reset selection to L_PAGE + */ + XQspiPs_SetLqspiConfigReg(QspiInstancePtr, + LqspiCrReg & (~XQSPIPS_LQSPI_CR_U_PAGE_MASK)); + + fsbl_printf(DEBUG_INFO, "stacked - lower CS \n\r"); + + /* + * Assert the FLASH chip select. + */ + XQspiPs_SetSlaveSelect(QspiInstancePtr); + } + } + + return XST_SUCCESS; +} + + + +/****************************************************************************** +* +* This functions selects the current bank +* +* @param BankSel is the bank to be selected in the flash device(s). +* +* @return XST_SUCCESS if bank selected +* XST_FAILURE if selection failed +* @note None. +* +******************************************************************************/ +u32 SendBankSelect(u8 BankSel) +{ + u32 Status; + + /* + * bank select commands for Micron and Spansion are different + */ + if (QspiFlashMake == MICRON_ID) { + /* + * For micron command WREN should be sent first + * except for some specific feature set + */ + WriteBuffer[COMMAND_OFFSET] = WRITE_ENABLE_CMD; + Status = XQspiPs_PolledTransfer(QspiInstancePtr, WriteBuffer, NULL, + WRITE_ENABLE_CMD_SIZE); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + + /* + * Send the Extended address register write command + * written, no receive buffer required + */ + WriteBuffer[COMMAND_OFFSET] = EXTADD_REG_WR; + WriteBuffer[ADDRESS_1_OFFSET] = BankSel; + Status = XQspiPs_PolledTransfer(QspiInstancePtr, WriteBuffer, NULL, + BANK_SEL_SIZE); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + } + + if (QspiFlashMake == SPANSION_ID) { + WriteBuffer[COMMAND_OFFSET] = BANK_REG_WR; + WriteBuffer[ADDRESS_1_OFFSET] = BankSel; + + /* + * Send the Extended address register write command + * written, no receive buffer required + */ + Status = XQspiPs_PolledTransfer(QspiInstancePtr, WriteBuffer, NULL, + BANK_SEL_SIZE); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + } + + /* + * For testing - Read bank to verify + */ + if (QspiFlashMake == SPANSION_ID) { + WriteBuffer[COMMAND_OFFSET] = BANK_REG_RD; + WriteBuffer[ADDRESS_1_OFFSET] = 0x00; + + /* + * Send the Extended address register write command + * written, no receive buffer required + */ + Status = XQspiPs_PolledTransfer(QspiInstancePtr, WriteBuffer, ReadBuffer, + BANK_SEL_SIZE); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + } + + if (QspiFlashMake == MICRON_ID) { + WriteBuffer[COMMAND_OFFSET] = EXTADD_REG_RD; + WriteBuffer[ADDRESS_1_OFFSET] = 0x00; + + /* + * Send the Extended address register write command + * written, no receive buffer required + */ + Status = XQspiPs_PolledTransfer(QspiInstancePtr, WriteBuffer, ReadBuffer, + BANK_SEL_SIZE); + if (Status != XST_SUCCESS) { + return XST_FAILURE; + } + } + + if (ReadBuffer[1] != BankSel) { + fsbl_printf(DEBUG_INFO, "BankSel %d != Register Read %d\n\r", BankSel, + ReadBuffer[1]); + return XST_FAILURE; + } + + return XST_SUCCESS; +} +#endif + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/qspi.h b/quad/xsdk_workspace/zybo_fsbl/src/qspi.h new file mode 100644 index 0000000000000000000000000000000000000000..9bac79c382d68927fca61df4d27ae8c0219f0dac --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/qspi.h @@ -0,0 +1,133 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file qspi.h +* +* This file contains the interface for the QSPI FLASH functionality +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a ecm 01/10/10 Initial release +* 3.00a mb 01/09/12 Added the Delay Values defines for qspi +* 5.00a sgd 05/17/13 Added Flash Size > 128Mbit support +* Dual Stack support +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___QSPI_H___ +#define ___QSPI_H___ + +#include "fsbl.h" +#ifdef __cplusplus +extern "C" { +#endif + +/***************************** Include Files *********************************/ +#include "fsbl.h" + +/************************** Constant Definitions *****************************/ +#define SINGLE_FLASH_CONNECTION 0 +#define DUAL_STACK_CONNECTION 1 +#define DUAL_PARALLEL_CONNECTION 2 +#define FLASH_SIZE_16MB 0x1000000 + +/* + * Bank mask + */ +#define BANKMASK 0xF000000 + +/* + * Identification of Flash + * Micron: + * Byte 0 is Manufacturer ID; + * Byte 1 is first byte of Device ID - 0xBB or 0xBA + * Byte 2 is second byte of Device ID describes flash size: + * 128Mbit : 0x18; 256Mbit : 0x19; 512Mbit : 0x20 + * Spansion: + * Byte 0 is Manufacturer ID; + * Byte 1 is Device ID - Memory Interface type - 0x20 or 0x02 + * Byte 2 is second byte of Device ID describes flash size: + * 128Mbit : 0x18; 256Mbit : 0x19; 512Mbit : 0x20 + */ + +#define MICRON_ID 0x20 +#define SPANSION_ID 0x01 +#define WINBOND_ID 0xEF + +#define FLASH_SIZE_ID_128M 0x18 +#define FLASH_SIZE_ID_256M 0x19 +#define FLASH_SIZE_ID_512M 0x20 +#define FLASH_SIZE_ID_1G 0x21 + +/* + * Size in bytes + */ +#define FLASH_SIZE_128M 0x1000000 +#define FLASH_SIZE_256M 0x2000000 +#define FLASH_SIZE_512M 0x4000000 +#define FLASH_SIZE_1G 0x8000000 + +/************************** Function Prototypes ******************************/ +u32 InitQspi(void); + +u32 QspiAccess( u32 SourceAddress, + u32 DestinationAddress, + u32 LengthBytes); + +u32 FlashReadID(void); +u32 SendBankSelect(u8 BankSel); +/************************** Variable Definitions *****************************/ + + +#ifdef __cplusplus +} +#endif + + +#endif /* ___QSPI_H___ */ + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/rsa.c b/quad/xsdk_workspace/zybo_fsbl/src/rsa.c new file mode 100644 index 0000000000000000000000000000000000000000..1f43b605330bc6b1c4ef6a03be409cff4c5fb034 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/rsa.c @@ -0,0 +1,353 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file rsa.c +* +* Contains code for the RSA authentication +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 4.00a sgd 02/28/13 Initial release +* 6.00a kc 07/30/13 Added FSBL_DEBUG_RSA to print more RSA buffers +* Fix for CR#724165 - Partition Header used by FSBL is +* not authenticated +* Fix for CR#724166 - FSBL doesn’t use PPK authenticated +* by Boot ROM for authenticating +* the Partition images +* Fix for CR#722979 - Provide customer-friendly +* changelogs in FSBL +* </pre> +* +* @note +* +******************************************************************************/ + +/***************************** Include Files *********************************/ +#include "fsbl.h" +#include "rsa.h" + +#ifdef XPAR_XWDTPS_0_BASEADDR +#include "xwdtps.h" +#endif + +/************************** Constant Definitions *****************************/ + +/**************************** Type Definitions *******************************/ + + +/***************** Macros (Inline Functions) Definitions *********************/ + + +/************************** Function Prototypes ******************************/ +#ifdef XPAR_XWDTPS_0_BASEADDR +extern XWdtPs Watchdog; /* Instance of WatchDog Timer */ +#endif + + +/************************** Variable Definitions *****************************/ + +#ifdef RSA_SUPPORT +static u8 *PpkModular; +static u8 *PpkModularEx; +static u32 PpkExp; + + +extern u32 FsblLength; + +void FsblPrintArray (u8 *Buf, u32 Len, char *Str) +{ +#ifdef FSBL_DEBUG_RSA + int Index; + fsbl_printf(DEBUG_INFO, "%s START\r\n", Str); + for (Index=0;Index<Len;Index++) + { + fsbl_printf(DEBUG_INFO, "%02x",Buf[Index]); + if ((Index+1)%16 == 0){ + fsbl_printf(DEBUG_INFO, "\r\n"); + } + } + fsbl_printf(DEBUG_INFO, "\r\n %s END\r\n",Str); +#endif + return; +} + + +/*****************************************************************************/ +/** +* +* This function is used to set ppk pointer to ppk in OCM +* +* @param None +* +* @return +* +* @note None +* +******************************************************************************/ + +void SetPpk(void ) +{ + u32 PadSize; + u8 *PpkPtr; + + /* + * Set PpkPtr to PPK in OCM + */ + + /* + * Skip FSBL Length + */ + PpkPtr = (u8 *)(FsblLength); + /* + * Skip to 64 byte Boundary + */ + PadSize = ((u32)PpkPtr % 64); + if(PadSize != 0) + { + PpkPtr += (64 - PadSize); + } + + /* + * Increment the pointer by authentication Header size + */ + PpkPtr += RSA_HEADER_SIZE; + + /* + * Increment the pointer by Magic word size + */ + PpkPtr += RSA_MAGIC_WORD_SIZE; + + /* + * Set pointer to PPK + */ + PpkModular = (u8 *)PpkPtr; + PpkPtr += RSA_PPK_MODULAR_SIZE; + PpkModularEx = (u8 *)PpkPtr; + PpkPtr += RSA_PPK_MODULAR_EXT_SIZE; + PpkExp = *((u32 *)PpkPtr); + + return; +} + + +/*****************************************************************************/ +/** +* +* This function Authenticate Partition Signature +* +* @param Partition header pointer +* +* @return +* - XST_SUCCESS if Authentication passed +* - XST_FAILURE if Authentication failed +* +* @note None +* +******************************************************************************/ +u32 AuthenticatePartition(u8 *Buffer, u32 Size) +{ + u8 DecryptSignature[256]; + u8 HashSignature[32]; + u8 *SpkModular; + u8 *SpkModularEx; + u32 SpkExp; + u8 *SignaturePtr; + u32 Status; + +#ifdef XPAR_XWDTPS_0_BASEADDR + /* + * Prevent WDT reset + */ + XWdtPs_RestartWdt(&Watchdog); +#endif + + /* + * Point to Authentication Certificate + */ + SignaturePtr = (u8 *)(Buffer + Size - RSA_SIGNATURE_SIZE); + + /* + * Increment the pointer by authentication Header size + */ + SignaturePtr += RSA_HEADER_SIZE; + + /* + * Increment the pointer by Magic word size + */ + SignaturePtr += RSA_MAGIC_WORD_SIZE; + + /* + * Increment the pointer beyond the PPK + */ + SignaturePtr += RSA_PPK_MODULAR_SIZE; + SignaturePtr += RSA_PPK_MODULAR_EXT_SIZE; + SignaturePtr += RSA_PPK_EXPO_SIZE; + + /* + * Calculate Hash Signature + */ + sha_256((u8 *)SignaturePtr, (RSA_SPK_MODULAR_EXT_SIZE + + RSA_SPK_EXPO_SIZE + RSA_SPK_MODULAR_SIZE), + HashSignature); + FsblPrintArray(HashSignature, 32, "SPK Hash Calculated"); + + /* + * Extract SPK signature + */ + SpkModular = (u8 *)SignaturePtr; + SignaturePtr += RSA_SPK_MODULAR_SIZE; + SpkModularEx = (u8 *)SignaturePtr; + SignaturePtr += RSA_SPK_MODULAR_EXT_SIZE; + SpkExp = *((u32 *)SignaturePtr); + SignaturePtr += RSA_SPK_EXPO_SIZE; + + /* + * Decrypt SPK Signature + */ + rsa2048_pubexp((RSA_NUMBER)DecryptSignature, + (RSA_NUMBER)SignaturePtr, + (u32)PpkExp, + (RSA_NUMBER)PpkModular, + (RSA_NUMBER)PpkModularEx); + FsblPrintArray(DecryptSignature, RSA_SPK_SIGNATURE_SIZE, + "SPK Decrypted Hash"); + + + Status = RecreatePaddingAndCheck(DecryptSignature, HashSignature); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO, "Partition SPK Signature " + "Authentication failed\r\n"); + return XST_FAILURE; + } + SignaturePtr += RSA_SPK_SIGNATURE_SIZE; + + /* + * Decrypt Partition Signature + */ + rsa2048_pubexp((RSA_NUMBER)DecryptSignature, + (RSA_NUMBER)SignaturePtr, + (u32)SpkExp, + (RSA_NUMBER)SpkModular, + (RSA_NUMBER)SpkModularEx); + FsblPrintArray(DecryptSignature, RSA_PARTITION_SIGNATURE_SIZE, + "Partition Decrypted Hash"); + + /* + * Partition Authentication + * Calculate Hash Signature + */ + sha_256((u8 *)Buffer, + (Size - RSA_PARTITION_SIGNATURE_SIZE), + HashSignature); + FsblPrintArray(HashSignature, 32, + "Partition Hash Calculated"); + + Status = RecreatePaddingAndCheck(DecryptSignature, HashSignature); + if (Status != XST_SUCCESS) { + fsbl_printf(DEBUG_INFO, "Partition Signature " + "Authentication failed\r\n"); + return XST_FAILURE; + } + + return XST_SUCCESS; +} + + +/*****************************************************************************/ +/** +* +* This function recreates the and check signature +* +* @param Partition signature +* @param Partition hash value which includes boot header, partition data +* @return +* - XST_SUCCESS if check passed +* - XST_FAILURE if check failed +* +* @note None +* +******************************************************************************/ +u32 RecreatePaddingAndCheck(u8 *signature, u8 *hash) +{ + u8 T_padding[] = {0x30, 0x31, 0x30, 0x0D, 0x06, 0x09, 0x60, 0x86, 0x48, + 0x01, 0x65, 0x03, 0x04, 0x02, 0x01, 0x05, 0x00, 0x04, 0x20 }; + u8 * pad_ptr = signature + 256; + u32 pad = 256 - 3 - 19 - 32; + u32 ii; + + /* + * Re-Create PKCS#1v1.5 Padding + * MSB ----------------------------------------------------LSB + * 0x0 || 0x1 || 0xFF(for 202 bytes) || 0x0 || T_padding || SHA256 Hash + */ + if (*--pad_ptr != 0x00 || *--pad_ptr != 0x01) { + return XST_FAILURE; + } + + for (ii = 0; ii < pad; ii++) { + if (*--pad_ptr != 0xFF) { + return XST_FAILURE; + } + } + + if (*--pad_ptr != 0x00) { + return XST_FAILURE; + } + + for (ii = 0; ii < sizeof(T_padding); ii++) { + if (*--pad_ptr != T_padding[ii]) { + return XST_FAILURE; + } + } + + for (ii = 0; ii < 32; ii++) { + if (*--pad_ptr != hash[ii]) + return XST_FAILURE; + } + + return XST_SUCCESS; +} +#endif diff --git a/quad/xsdk_workspace/zybo_fsbl/src/rsa.h b/quad/xsdk_workspace/zybo_fsbl/src/rsa.h new file mode 100644 index 0000000000000000000000000000000000000000..bb1c5f37adeb8b5337cc9c268f06607d0e5463af --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/rsa.h @@ -0,0 +1,187 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file rsa.h +* +* This file contains the RSA algorithm functions +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 4.00a sg 02/28/13 Initial release +* +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___RSA_H___ +#define ___RSA_H___ + +#ifdef __cplusplus +extern "C" { +#endif +/***************************** Include Files *********************************/ + +/* + * Digit size selection (32 or 16-bit). If supported by the CPU/compiler, + * 32-bit digits are approximately 4 times faster + */ + +//#define RSA_DIGIT_16 +#define RSA_DIGIT_32 + +/* + * RSA loop unrolling selection + * RSA main loop can be unrolled 2, 4 or 8 ways + */ +#define RSA_UNROLL 1 + +/* + * Select if ARM-optimized code is to be used. Only GCC for ARM is supported + */ +//#define RSA_ARM_OPTIMIZED + +/* + * Check the compatibility of the selection + */ +#if defined(RSA_DIGIT_16) && defined(RSA_DIGIT_32) + #error Please select a digit size +#endif +#if !defined(RSA_DIGIT_16) && !defined(RSA_DIGIT_32) + #error Please select just one digit size +#endif +#if (!defined(__GNUC__) || !defined(__arm__)) && defined(RSA_ARM_OPTIMIZED) + #error Assembly level code is only supported for the GCC/ARM combination +#endif +#if (RSA_UNROLL != 1) && (RSA_UNROLL != 2) && (RSA_UNROLL != 4) && (RSA_UNROLL != 8) + #error Only 1, 2, 4, and 8 unrolling are supported +#endif + +#ifdef RSA_DIGIT_16 +#define RSA_DIGIT unsigned short +#define RSA_SDIGIT short +#define RSA_DDIGIT unsigned long +#endif +#ifdef RSA_DIGIT_32 +#define RSA_DIGIT unsigned long +#define RSA_SDIGIT long +#define RSA_DDIGIT unsigned long long +#endif + +#define RSA_NUMBER RSA_DIGIT * +#define RSA_NBITS 2048 +#define RSA_NDIGITS (RSA_NBITS/(sizeof(RSA_DIGIT)*8)) +#define RSA_NBYTES (RSA_NDIGITS*sizeof(RSA_DIGIT)) + +/* + * Double-digit to single digit conversion + */ +#define RSA_MSB(x) (x >> (sizeof(RSA_DIGIT)*8)) +#define RSA_LSB(x) (x & (RSA_DIGIT)~0) + +#define SHA_BLKSIZE 512 +#define SHA_BLKBYTES (SHA_BLKSIZE/8) +#define SHA_BLKWORDS (SHA_BLKBYTES/4) + +#define SHA_VALSIZE 256 +#define SHA_VALBYTES (SHA_VALSIZE/8) +#define SHA_VALWORDS (SHA_VALBYTES/4) + +#define RSA_PPK_MODULAR_SIZE 256 +#define RSA_PPK_MODULAR_EXT_SIZE 256 +#define RSA_PPK_EXPO_SIZE 64 +#define RSA_SPK_MODULAR_SIZE 256 +#define RSA_SPK_MODULAR_EXT_SIZE 256 +#define RSA_SPK_EXPO_SIZE 64 +#define RSA_SPK_SIGNATURE_SIZE 256 +#define RSA_PARTITION_SIGNATURE_SIZE 256 +#define RSA_SIGNATURE_SIZE 0x6C0 /* Signature size in bytes */ +#define RSA_HEADER_SIZE 4 /* Signature header size in bytes */ +#define RSA_MAGIC_WORD_SIZE 60 /* Magic word size in bytes */ + +/* + * SHA-256 context structure + * Includes SHA-256 state, coalescing buffer to collect the processed strings, and + * total byte length counter (used both to manage the buffer and for padding) + */ +typedef struct +{ + unsigned int state[8]; + unsigned char buffer[SHA_BLKBYTES]; + unsigned long long bytes; +} sha2_context; + +/* + * RSA-2048 user interfaces + */ +void rsa2048_exp(const unsigned char *base, const unsigned char * modular, + const unsigned char *modular_ext, const unsigned char *exponent, + unsigned char *result); +void rsa2048_pubexp(RSA_NUMBER a, RSA_NUMBER x, + unsigned long e, RSA_NUMBER m, RSA_NUMBER rrm); + +/* + * SHA-256 user interfaces + */ +void sha_256(const unsigned char *in, const unsigned int size, unsigned char *out); +void sha2_starts(sha2_context *ctx); +void sha2_update(sha2_context *ctx, unsigned char* input, unsigned int ilen); +void sha2_finish(sha2_context *ctx, unsigned char* output); + +/* + * Preprocessing interface (pre-computation of R*R mod M) + */ +void modular_ext(const unsigned char *modular, unsigned char *res); + +void SetPpk(void ); +u32 AuthenticatePartition(u8 *Buffer, u32 Size); +u32 RecreatePaddingAndCheck(u8 *signature, u8 *hash); + +#ifdef __cplusplus +} +#endif + +#endif /* ___RSA_H___ */ diff --git a/quad/xsdk_workspace/zybo_fsbl/src/sd.c b/quad/xsdk_workspace/zybo_fsbl/src/sd.c new file mode 100644 index 0000000000000000000000000000000000000000..b0e4b9ca34c35147259b83a15f7a2d7f63e12578 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/sd.c @@ -0,0 +1,191 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file sd.c +* +* Contains code for the SD card FLASH functionality. +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a jz 04/28/11 Initial release +* +* </pre> +* +* @note +* +******************************************************************************/ + +/***************************** Include Files *********************************/ +#include "xparameters.h" +#include "fsbl.h" +#ifdef XPAR_PS7_SD_0_S_AXI_BASEADDR +#include "xstatus.h" + +#include "ff.h" +#include "sd.h" + +/************************** Constant Definitions *****************************/ + +/**************************** Type Definitions *******************************/ + +/***************** Macros (Inline Functions) Definitions *********************/ + +/************************** Function Prototypes ******************************/ + +/************************** Variable Definitions *****************************/ + +extern u32 FlashReadBaseAddress; + + +static FIL fil; /* File object */ +static FATFS fatfs; +static char buffer[32]; +static char *boot_file = buffer; + +/******************************************************************************/ +/******************************************************************************/ +/** +* +* This function initializes the controller for the SD FLASH interface. +* +* @param filename of the file that is to be used +* +* @return +* - XST_SUCCESS if the controller initializes correctly +* - XST_FAILURE if the controller fails to initializes correctly +* +* @note None. +* +****************************************************************************/ +u32 InitSD(const char *filename) +{ + + FRESULT rc; + + /* Register volume work area, initialize device */ + rc = f_mount(0, &fatfs); + fsbl_printf(DEBUG_INFO,"SD: rc= %.8x\n\r", rc); + + if (rc != FR_OK) { + return XST_FAILURE; + } + + strcpy_rom(buffer, filename); + boot_file = (char *)buffer; + FlashReadBaseAddress = XPAR_PS7_SD_0_S_AXI_BASEADDR; + + rc = f_open(&fil, boot_file, FA_READ); + if (rc) { + fsbl_printf(DEBUG_GENERAL,"SD: Unable to open file %s: %d\n", boot_file, rc); + return XST_FAILURE; + } + + return XST_SUCCESS; + +} + +/******************************************************************************/ +/** +* +* This function provides the SD FLASH interface for the Simplified header +* functionality. +* +* @param SourceAddress is address in FLASH data space +* @param DestinationAddress is address in OCM data space +* @param LengthBytes is the number of bytes to move +* +* @return +* - XST_SUCCESS if the write completes correctly +* - XST_FAILURE if the write fails to completes correctly +* +* @note None. +* +****************************************************************************/ +u32 SDAccess( u32 SourceAddress, u32 DestinationAddress, u32 LengthBytes) +{ + + FRESULT rc; /* Result code */ + UINT br; + + rc = f_lseek(&fil, SourceAddress); + if (rc) { + fsbl_printf(DEBUG_INFO,"SD: Unable to seek to %x\n", SourceAddress); + return XST_FAILURE; + } + + rc = f_read(&fil, (void*)DestinationAddress, LengthBytes, &br); + + if (rc) { + fsbl_printf(DEBUG_GENERAL,"*** ERROR: f_read returned %d\r\n", rc); + } + + return XST_SUCCESS; + +} /* End of SDAccess */ + + +/******************************************************************************/ +/** +* +* This function closes the file object +* +* @param None +* +* @return None. +* +* @note None. +* +****************************************************************************/ +void ReleaseSD(void) { + + f_close(&fil); + return; + + +} +#endif + + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/sd.h b/quad/xsdk_workspace/zybo_fsbl/src/sd.h new file mode 100644 index 0000000000000000000000000000000000000000..9de76281fcca143a55476b5e3002a146ee8a30c4 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/sd.h @@ -0,0 +1,87 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +* +*******************************************************************************/ +/*****************************************************************************/ +/** +* +* @file sd.h +* +* This file contains the interface for the Secure Digital (SD) card +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- ------------------------------------------------------- +* 1.00a bh 03/10/11 Initial release +* +* </pre> +* +* @note +* +******************************************************************************/ +#ifndef ___SD_H___ +#define ___SD_H___ + + +#ifdef __cplusplus +extern "C" { +#endif + + +/************************** Function Prototypes ******************************/ + +#ifdef XPAR_PS7_SD_0_S_AXI_BASEADDR +u32 InitSD(const char *); + +u32 SDAccess( u32 SourceAddress, + u32 DestinationAddress, + u32 LengthWords); + +void ReleaseSD(void); +#endif +/************************** Variable Definitions *****************************/ +#ifdef __cplusplus +} +#endif + + +#endif /* ___SD_H___ */ + diff --git a/quad/xsdk_workspace/zybo_fsbl/src/sd_hardware.h b/quad/xsdk_workspace/zybo_fsbl/src/sd_hardware.h new file mode 100644 index 0000000000000000000000000000000000000000..16872f4f9257779db8d3a9c2c67aa4106f6befb1 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl/src/sd_hardware.h @@ -0,0 +1,158 @@ +/****************************************************************************** +* +* (c) Copyright 2012-2013 Xilinx, Inc. All rights reserved. +* +* This file contains confidential and proprietary information of Xilinx, Inc. +* and is protected under U.S. and international copyright and other +* intellectual property laws. +* +* DISCLAIMER +* This disclaimer is not a license and does not grant any rights to the +* materials distributed herewith. Except as otherwise provided in a valid +* license issued to you by Xilinx, and to the maximum extent permitted by +* applicable law: (1) THESE MATERIALS ARE MADE AVAILABLE "AS IS" AND WITH ALL +* FAULTS, AND XILINX HEREBY DISCLAIMS ALL WARRANTIES AND CONDITIONS, EXPRESS, +* IMPLIED, OR STATUTORY, INCLUDING BUT NOT LIMITED TO WARRANTIES OF +* MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR ANY PARTICULAR PURPOSE; +* and (2) Xilinx shall not be liable (whether in contract or tort, including +* negligence, or under any other theory of liability) for any loss or damage +* of any kind or nature related to, arising under or in connection with these +* materials, including for any direct, or any indirect, special, incidental, +* or consequential loss or damage (including loss of data, profits, goodwill, +* or any type of loss or damage suffered as a result of any action brought by +* a third party) even if such damage or loss was reasonably foreseeable or +* Xilinx had been advised of the possibility of the same. +* +* CRITICAL APPLICATIONS +* Xilinx products are not designed or intended to be fail-safe, or for use in +* any application requiring fail-safe performance, such as life-support or +* safety devices or systems, Class III medical devices, nuclear facilities, +* applications related to the deployment of airbags, or any other applications +* that could lead to death, personal injury, or severe property or +* environmental damage (individually and collectively, "Critical +* Applications"). Customer assumes the sole risk and liability of any use of +* Xilinx products in Critical Applications, subject only to applicable laws +* and regulations governing limitations on product liability. +* +* THIS COPYRIGHT NOTICE AND DISCLAIMER MUST BE RETAINED AS PART OF THIS FILE +* AT ALL TIMES. +******************************************************************************/ +/*****************************************************************************/ +/** +* @file sd_hardware.h +* +* Controller register and bit definitions +* +* <pre> +* MODIFICATION HISTORY: +* +* Ver Who Date Changes +* ----- ---- -------- --------------------------------------------------- +* 1.00a bh 02/01/11 Initial version, +* </pre> +* +* @note None. +* +******************************************************************************/ +#ifndef __SD_HARDWARE_H__ +#define __SD_HARDWARE_H__ + +#define SD_BLOCK_SZ 0x200 +#define SD_CLK_400K 400000 +#define SD_CLK_50M 50000000 +#define SD_CLK_25M 25000000 +#define SD_HS_SUPPORT 0x2 +#define SD_4BIT_SUPPORT 0x5 + +#define SD_DMA_ADDR_R 0x00 +#define SD_BLOCK_SZ_R 0x04 +#define SD_BLOCK_CNT_R 0x06 + +#define SD_ARG_R 0x08 + +#define SD_TRNS_MODE_R 0x0C +#define SD_TRNS_DMA 0x01 +#define SD_TRNS_BLK_CNT_EN 0x02 +#define SD_TRNS_ACMD12 0x04 +#define SD_TRNS_READ 0x10 +#define SD_TRNS_MULTI 0x20 + +#define SD_CMD_R 0x0E +#define SD_CMD_RESP_NONE 0x00 +#define SD_CMD_RESP_136 0x01 +#define SD_CMD_RESP_48 0x02 +#define SD_CMD_RESP_48_BUSY 0x03 +#define SD_CMD_CRC 0x08 +#define SD_CMD_INDEX 0x10 +#define SD_CMD_DATA 0x20 + +#define SD_RSP_R 0x10 + +#define SD_BUFF_R 0x20 + +#define SD_PRES_STATE_R 0x24 +#define SD_CMD_INHIBIT 0x00000001 +#define SD_DATA_INHIBIT 0x00000002 +#define SD_WRITE_ACTIVE 0x00000100 +#define SD_READ_ACTIVE 0x00000200 +#define SD_CARD_INS 0x00010000 +#define SD_CARD_WP 0x00080000 + +#define SD_HOST_CTRL_R 0x28 +#define SD_HOST_4BIT 0x02 +#define SD_HOST_HS 0x04 +#define SD_HOST_ADMA1 0x08 +#define SD_HOST_ADMA2 0x10 + +#define SD_PWR_CTRL_R 0x29 +#define SD_POWER_ON 0x01 +#define SD_POWER_18 0x0A +#define SD_POWER_30 0x0C +#define SD_POWER_33 0x0E + +#define SD_BLCK_GAP_CTL_R 0x2A + +#define SD_WAKE_CTL_R 0x2B + +#define SD_CLK_CTL_R 0x2C +#define SD_DIV_SHIFT 8 +#define SD_CLK_SD_EN 0x0004 +#define SD_CLK_INT_STABLE 0x0002 +#define SD_CLK_INT_EN 0x0001 + +#define SD_TIMEOUT_CTL_R 0x2E + +#define SD_SOFT_RST_R 0x2F +#define SD_RST_ALL 0x01 +#define SD_RST_CMD 0x02 +#define SD_RST_DATA 0x04 + +#define SD_INT_STAT_R 0x30 +#define SD_INT_ENA_R 0x34 +#define SD_SIG_ENA_R 0x38 +#define SD_INT_CMD_CMPL 0x00000001 +#define SD_INT_TRNS_CMPL 0x00000002 +#define SD_INT_DMA 0x00000008 +#define SD_INT_ERROR 0x00008000 +#define SD_INT_ERR_CTIMEOUT 0x00010000 +#define SD_INT_ERR_CCRC 0x00020000 +#define SD_INT_ERR_CEB 0x00040000 +#define SD_INT_ERR_IDX 0x00080000 +#define SD_INT_ERR_DTIMEOUT 0x00100000 +#define SD_INT_ERR_DCRC 0x00200000 +#define SD_INT_ERR_DEB 0x00400000 +#define SD_INT_ERR_CLMT 0x00800000 +#define SD_INT_ERR_ACMD12 0x01000000 +#define SD_INT_ERR_ADMA 0x02000000 +#define SD_INT_ERR_TRESP 0x10000000 + +#define SD_CAPABILITIES_R 0x40 + +#define SD_ADMA_ADDR_R 0x58 +#define DESC_ATBR_VALID (0x1 << 0) +#define DESC_ATBR_END (0x1 << 1) +#define DESC_ATBR_INT (0x1 << 2) +#define DESC_ATBR_ACT_TRAN (0x2 << 4) +#define DESC_ATBR_LEN_SHIFT 16 + +#endif diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/.cproject b/quad/xsdk_workspace/zybo_fsbl_bsp/.cproject new file mode 100644 index 0000000000000000000000000000000000000000..d01a3047c9fa0ed118a5358404b92ab2b2c2fc31 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/.cproject @@ -0,0 +1,15 @@ +<?xml version="1.0" encoding="UTF-8" standalone="no"?> +<?fileVersion 4.0.0?> + +<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage"> + <storageModule moduleId="org.eclipse.cdt.core.settings"> + <cconfiguration id="org.eclipse.cdt.core.default.config.145391090"> + <storageModule buildSystemId="org.eclipse.cdt.core.defaultConfigDataProvider" id="org.eclipse.cdt.core.default.config.145391090" moduleId="org.eclipse.cdt.core.settings" name="Configuration"> + <externalSettings/> + <extensions/> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> + </cconfiguration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/> +</cproject> diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/.project b/quad/xsdk_workspace/zybo_fsbl_bsp/.project new file mode 100644 index 0000000000000000000000000000000000000000..db7920e2db6569999084baf805b3d45df40aab13 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/.project @@ -0,0 +1,76 @@ +<?xml version="1.0" encoding="UTF-8"?> +<projectDescription> + <name>zybo_fsbl_bsp</name> + <comment></comment> + <projects> + <project>system_hw_platform</project> + </projects> + <buildSpec> + <buildCommand> + <name>org.eclipse.cdt.make.core.makeBuilder</name> + <arguments> + <dictionary> + <key>org.eclipse.cdt.core.errorOutputParser</key> + <value>org.eclipse.cdt.core.GASErrorParser;org.eclipse.cdt.core.GCCErrorParser;org.eclipse.cdt.core.GLDErrorParser;org.eclipse.cdt.core.GmakeErrorParser;org.eclipse.cdt.core.VCErrorParser;org.eclipse.cdt.core.CWDLocator;org.eclipse.cdt.core.MakeErrorParser;</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.append_environment</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.arguments</key> + <value></value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.command</key> + <value>make</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.target.auto</key> + <value>all</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.target.clean</key> + <value>clean</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.build.target.inc</key> + <value>all</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enableAutoBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enableCleanBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enableFullBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.enabledIncrementalBuild</key> + <value>true</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.environment</key> + <value></value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.stopOnError</key> + <value>false</value> + </dictionary> + <dictionary> + <key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key> + <value>true</value> + </dictionary> + </arguments> + </buildCommand> + </buildSpec> + <natures> + <nature>com.xilinx.sdk.sw.SwProjectNature</nature> + <nature>org.eclipse.cdt.core.cnature</nature> + <nature>org.eclipse.cdt.make.core.makeNature</nature> + </natures> +</projectDescription> diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/.sdkproject b/quad/xsdk_workspace/zybo_fsbl_bsp/.sdkproject new file mode 100644 index 0000000000000000000000000000000000000000..3135ec9f796f86108f3510421221835514fcc15f --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/.sdkproject @@ -0,0 +1,3 @@ +THIRPARTY=false +PROCESSOR=ps7_cortexa9_0 +MSS_FILE=system.mss diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/Makefile b/quad/xsdk_workspace/zybo_fsbl_bsp/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..fe2a0efc7cc39ff9edfdbb9064b229a72106cb58 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/Makefile @@ -0,0 +1,21 @@ +# Makefile generated by Xilinx SDK. + +-include libgen.options + +LIBRARIES = ${PROCESSOR}/lib/libxil.a +MSS = system.mss + +all: libs + @echo 'Finished building libraries' + +libs: $(LIBRARIES) + +$(LIBRARIES): $(MSS) + libgen -hw ${HWSPEC}\ + ${REPOSITORIES}\ + -pe ${PROCESSOR} \ + -log libgen.log \ + $(MSS) + +clean: + rm -rf ${PROCESSOR} diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/libgen.options b/quad/xsdk_workspace/zybo_fsbl_bsp/libgen.options new file mode 100644 index 0000000000000000000000000000000000000000..ac5ba396687b73316827155661d71b9247b953be --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/libgen.options @@ -0,0 +1,3 @@ +PROCESSOR=ps7_cortexa9_0 +REPOSITORIES= +HWSPEC=../system_hw_platform/system.xml diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/system.mss b/quad/xsdk_workspace/zybo_fsbl_bsp/system.mss new file mode 100644 index 0000000000000000000000000000000000000000..f6a16bfdc89cf14e12ce15914d7218be2055b907 --- /dev/null +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/system.mss @@ -0,0 +1,291 @@ + + PARAMETER VERSION = 2.2.0 + + +BEGIN OS + PARAMETER OS_NAME = standalone + PARAMETER OS_VER = 3.11.a + PARAMETER PROC_INSTANCE = ps7_cortexa9_0 + PARAMETER STDIN = ps7_uart_0 + PARAMETER STDOUT = ps7_uart_0 +END + + +BEGIN PROCESSOR + PARAMETER DRIVER_NAME = cpu_cortexa9 + PARAMETER DRIVER_VER = 1.01.a + PARAMETER HW_INSTANCE = ps7_cortexa9_0 +END + + +BEGIN DRIVER + PARAMETER DRIVER_NAME = tmrctr + PARAMETER DRIVER_VER = 2.05.a + PARAMETER HW_INSTANCE = axi_timer_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = gpio + PARAMETER DRIVER_VER = 3.01.a + PARAMETER HW_INSTANCE = btns_4bits_tri_io +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_2 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_afi_3 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_coresight_comp_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ddr_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ddrc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = devcfg + PARAMETER DRIVER_VER = 2.04.a + PARAMETER HW_INSTANCE = ps7_dev_cfg_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = dmaps + PARAMETER DRIVER_VER = 1.06.a + PARAMETER HW_INSTANCE = ps7_dma_ns +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = dmaps + PARAMETER DRIVER_VER = 1.06.a + PARAMETER HW_INSTANCE = ps7_dma_s +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = emacps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_ethernet_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_globaltimer_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = gpiops + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_gpio_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_gpv_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = iicps + PARAMETER DRIVER_VER = 1.04.a + PARAMETER HW_INSTANCE = ps7_i2c_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_intc_dist_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_iop_bus_config_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_l2cachec_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ocmc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = qspips + PARAMETER DRIVER_VER = 2.03.a + PARAMETER HW_INSTANCE = ps7_qspi_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_qspi_linear_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ram_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_ram_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_scuc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = scugic + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_scugic_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = scutimer + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_scutimer_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = scuwdt + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_scuwdt_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_sd_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = ps7_slcr_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = uartps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_uart_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = uartps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_uart_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = usbps + PARAMETER DRIVER_VER = 1.05.a + PARAMETER HW_INSTANCE = ps7_usb_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = xadcps + PARAMETER DRIVER_VER = 1.02.a + PARAMETER HW_INSTANCE = ps7_xadc_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_2 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_3 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_4 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_recorder_5 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_0 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_1 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_2 +END + +BEGIN DRIVER + PARAMETER DRIVER_NAME = generic + PARAMETER DRIVER_VER = 1.00.a + PARAMETER HW_INSTANCE = pwm_signal_out_wkillswitch_3 +END + +