diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index b10138c39575da2ca1ae9f16cbe95f1f56e4c3e2..0e81abf597779dfee2cd495ab6c4f602a003771d 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -1,7 +1,7 @@ image: ruby:2.3 before_script: - - apt-get update -qq && apt-get install -y -qq libbluetooth-dev cmake + - apt-get update -qq && apt-get install -y -qq libbluetooth-dev cmake valgrind stages: - build diff --git a/controls/DataAnalysisTool/Tool/BiquadFilter.m b/controls/DataAnalysisTool/Tool/BiquadFilter.m new file mode 100644 index 0000000000000000000000000000000000000000..ca1b93df2772ed74ce18267f1b344ca024711fdb --- /dev/null +++ b/controls/DataAnalysisTool/Tool/BiquadFilter.m @@ -0,0 +1,20 @@ +function out = BiquadFilter(input, Fs, Fc) + K = tan(pi * Fc / Fs); + Q = 0.5; + + norm = 1.0 / (1.0 + K/Q + K*K); + a0 = K*K*norm; + a1 = 2.0*a0; + a2 = a0; + b1 = 2.0*(K*K -1) * norm; + b2 = (1.0 - K/Q + K*K) * norm; + + prev = [0, 0]; + out = zeros(length(input), 1); + for n = 1:length(input) + leftSum = input(n) - prev(1)*b1 - prev(2)*b2; + out(n) = leftSum*a0 + prev(1)*a1 + prev(2)*a2; + + prev(2) = prev(1); + prev(1) = leftSum; + end \ No newline at end of file diff --git a/controls/DataAnalysisTool/Tool/simplePlots.m b/controls/DataAnalysisTool/Tool/simplePlots.m index f5a273a87e98b9a7c22784f3d57f2f81539952b4..a1087dfda7ccb05ff6f95b7edc4d465056ba6f77 100644 --- a/controls/DataAnalysisTool/Tool/simplePlots.m +++ b/controls/DataAnalysisTool/Tool/simplePlots.m @@ -163,7 +163,8 @@ linkaxes([ax1, ax2, ax3, ax4], 'x'); %% vel flow figure; ax2 = subplot(2,2,1); -plot(expData.Time.data, expData.OF_Integrate_X_Integrated.data - expData.X_pos_PID_Correction.data); hold on; +plot(expData.Time.data, expData.OF_Offset_Angle_Rotated_X.data - expData.RC_Pitch_Constant.data); hold on; +plot(expData.Time.data, expData.OF_Offset_Angle_Rotated_X.data); hold on; %plot(expData.Time.data, expData.X_Vel_Correction.data); hold on; %plot(expData.Time.data, [0; raw_derivative]); title('X velocity error'); @@ -174,7 +175,7 @@ title('x vel output'); ax3 = subplot(2,2,3); plot(expData.Time.data, expData.Pitch_PID_Correction.data); hold on; -plot(expData.Time.data, expData.VRPN_Pitch_Constant.data .* 10); +plot(expData.Time.data, expData.Pitch_trim_add_Sum.data .* 10); title('pitch output'); legend('output', 'Pitch x10'); @@ -216,13 +217,15 @@ plot(expData.Time.data, expData.Alt_Setpoint_Constant.data - expData.VRPN_Alt_Co title('Z error'); linkaxes([ax1, ax2, ax3], 'x'); %% -ax1 = subplot(2, 1, 1); +%ax1 = subplot(2, 1, 1); +figure; plot(expData.Time.data, expData.Lidar_Constant.data); hold on; plot(expData.Time.data, expData.VRPN_Alt_Constant.data); -legend('lidar', 'vrpn'); -ax2 = subplot(2, 1, 2); -plot(expData.Time.data, expData.Altitude_PID_Correction.data); +angle = sqrt(expData.Roll_Constant.data.^2 + expData.VRPN_Pitch_Constant.data.^2); +corrected = expData.Lidar_Constant.data .* cos(angle); +%plot(expData.Time.data, corrected); +legend('lidar', 'vrpn', 'angle corrected'); linkaxes([ax1, ax2], 'x'); @@ -245,8 +248,12 @@ plot(expData.Time.data, -filtered_sonar + alt_offset); legend('sonar', 'vrpn', 'dumb filter'); %% figure; + +offsetX = -expData.OF_Integrate_X_Integrated.data(1) - expData.VRPN_X_Constant.data(1); +offsetY = -expData.OF_Integrate_Y_Integrated.data(1) - expData.VRPN_Y_Constant.data(1); + ax1 = subplot(2, 1, 1); -plot(expData.Time.data, expData.OF_Integrate_X_Integrated.data); hold on; +plot(expData.Time.data, -expData.OF_Integrate_X_Integrated.data - offsetX); hold on; plot(expData.Time.data, expData.VRPN_X_Constant.data); legend('OF X Position', 'VRPN X Position'); xlabel('Time (s)'); @@ -254,7 +261,7 @@ ylabel('Displacement (m)'); hold off; ax2 = subplot(2, 1, 2); -plot(expData.Time.data, expData.OF_Integrate_Y_Integrated.data); hold on; +plot(expData.Time.data, -expData.OF_Integrate_Y_Integrated.data - offsetY); hold on; plot(expData.Time.data, expData.VRPN_Y_Constant.data); legend('OF Y Position', 'VRPN Y Position'); xlabel('Time (s)'); @@ -263,6 +270,7 @@ hold off; linkaxes([ax1, ax2]); + %% Integarted gyro yaw figure; plot(expData.Time.data, cumtrapz(expData.gyro_z.data + 0.0088)); hold on; diff --git a/controls/model/Library_Blocks/Derivative.slx b/controls/model/Library_Blocks/Derivative.slx new file mode 100644 index 0000000000000000000000000000000000000000..6367f56fe201f61ea4e48f3cdb2a452a5fc7d0ed Binary files /dev/null and b/controls/model/Library_Blocks/Derivative.slx differ diff --git a/controls/model/logAnalysis.m b/controls/model/logAnalysis.m index 8875fdb5cd7795e672a071bfd660023edcfd0815..ab699fbf2b87a485b3c08b32fab780b2f9637a51 100644 --- a/controls/model/logAnalysis.m +++ b/controls/model/logAnalysis.m @@ -25,7 +25,7 @@ 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_5ms); +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 @@ -51,7 +51,7 @@ roll_accel_mahony = mahony_reading.signals.values(indices_5ms, 1); % Plot x position controller output figure(1); ax1 = subplot(2, 2, 1); -stairs(time, x_vel_raw, '.-'); hold on; grid minor; +stairs(time, x_vel_setpoint, '.-'); hold on; grid minor; stairs(time_model_40ms, x_vel_setpoint_model_data, '.-'); hold off; title('X Position Controller Output'); xlabel('Time (s)'); @@ -91,7 +91,7 @@ linkaxes([ax1, ax2, ax3, ax4], 'x'); % Plot y position controller output figure(2); ax1 = subplot(2, 2, 1); -stairs(time, y_vel_raw, '.-'); hold on; grid minor; +stairs(time, y_vel_setpoint, '.-'); hold on; grid minor; stairs(time_model_40ms, y_vel_setpoint_model_data, '.-'); hold off; title('Y Position Controller Output'); xlabel('Time (s)'); @@ -131,29 +131,18 @@ linkaxes([ax1, ax2, ax3, ax4], 'x'); %% Plot z control structure % Plot z controller command -figure(3); ax1 = subplot(2, 1, 1); +figure(3); stairs(time, z_command, '.-'); hold on; grid minor; -stairs(time_model_5ms, z_command_model_data, '.-'); hold off; +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 -ax2 = subplot(2, 1, 2); -stairs(time, z_pos_raw, '.-'); 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'); - -linkaxes([ax1, ax2], 'x'); - %% Plot yaw control structure % Plot yaw controller output -figure(4); ax1 = subplot(2, 2, 1); +figure(4); ax1 = subplot(2, 1, 1); stairs(time, yawrate_setpoint,'.-'); hold on; grid minor; stairs(time_model_40ms, yawrate_setpoint_model_data, '.-'); hold off; title('Yaw Controller Output'); @@ -162,7 +151,7 @@ ylabel('d\psi/dt (rad/s)'); legend('Log', 'Model', 'location', 'northwest'); % Plot yaw controller command -ax2 = subplot(2, 2, 2); +ax2 = subplot(2, 1, 2); stairs(time, yaw_command, '.-'); hold on; grid minor; stairs(time_model_5ms, yaw_command_model_data, '.-'); hold off; title('Yaw Command'); @@ -170,21 +159,12 @@ xlabel('Time (s)'); ylabel('Command'); legend('Log', 'Model', 'location', 'northwest'); -% Plot yaw position -ax3 = subplot(2, 2, 3); -stairs(time, yaw_angle_raw, '.-'); 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'); - -linkaxes([ax1, ax2, ax3], 'x'); +linkaxes([ax1, ax2], 'x'); %% Plot PWM Commands figure(5); ax1 = subplot(2, 2, 1); stairs(time, PWM0,'.-'); hold on; grid minor; -%stairs(time_model_5ms, PWM0_model, '.-'); hold off; +stairs(time_model_5ms, PWM0_model, '.-'); hold off; title('PWM0 Value'); xlabel('Time (s)'); ylabel('PWM0 Command'); @@ -192,7 +172,7 @@ legend('Log', 'Model', 'location', 'northwest'); ax2 = subplot(2, 2, 2); stairs(time, PWM1,'.-'); hold on; grid minor; -%stairs(time_model_5ms, PWM1_model, '.-'); hold off; +stairs(time_model_5ms, PWM1_model, '.-'); hold off; title('PWM1 Value'); xlabel('Time (s)'); ylabel('PWM1 Command'); @@ -200,7 +180,7 @@ legend('Log', 'Model', 'location', 'northwest'); ax3 = subplot(2, 2, 3); stairs(time, PWM2,'.-'); hold on; grid minor; -%stairs(time_model_5ms, PWM2_model, '.-'); hold off; +stairs(time_model_5ms, PWM2_model, '.-'); hold off; title('PWM2 Value'); xlabel('Time (s)'); ylabel('PWM2 Command'); @@ -208,7 +188,7 @@ legend('Log', 'Model', 'location', 'northwest'); ax4 = subplot(2, 2, 4); stairs(time, PWM3,'.-'); hold on; grid minor; -%stairs(time_model_5ms, PWM3_model, '.-'); hold off; +stairs(time_model_5ms, PWM3_model, '.-'); hold off; title('PWM3 Value'); xlabel('Time (s)'); ylabel('PWM3 Command'); @@ -219,34 +199,31 @@ linkaxes([ax1, ax2, ax3, ax4], 'xy'); %% Plot output of complimentary filter figure(8); ax1 = subplot(2, 1, 1); -%stairs(time, pitch_measured_VRPN * (180/pi), '.-'); hold on; grid minor; -stairs(time, (pitch_measured_IMU) * (180/pi), '.-'); hold on; grid minor; -stairs(time_model_5ms, pitch_accel * (180/pi), '.-'); -%stairs(time_model_5ms, pitch_accel_mahony * (180/pi), '.-'); hold off; +stairs(time, pitch_measured_VRPN * (180/pi), '.-'); hold on; grid minor; +stairs(time, (pitch_measured_IMU) * (180/pi), '.-'); +stairs(time_model_5ms, (pitch_accel + 0.045) * (180/pi), '.-'); title('Pitch Complementary Filter Output'); xlabel('Time (s)'); ylabel('Pitch Angle (degrees)'); -%legend('VRPN','IMU', 'Model', 'Mahony', 'location', 'northwest'); -legend('IMU', 'Model','location', 'northwest'); +legend('VRPN','IMU', 'Model', 'location', 'northwest'); ax2 = subplot(2, 1, 2); -%stairs(time, roll_measured_VRPN * (180/pi), '.-'); hold on; grid minor; -stairs(time, roll_measured_IMU * (180/pi), '.-'); hold on; grid minor; +stairs(time, roll_measured_VRPN * (180/pi), '.-'); hold on; grid minor; +stairs(time, roll_measured_IMU * (180/pi), '.-'); stairs(time_model_5ms, roll_accel * (180/pi), '.-'); -%stairs(time_model_5ms, roll_accel_mahony * (180/pi), '.-'); hold off; title('Roll Complementary Filter Output'); xlabel('Time (s)'); ylabel('Roll Angle (degrees)'); -%legend('VRPN','IMU', 'Model', 'Mahony', 'location', 'northwest'); -legend('IMU', 'Model','location', 'northwest'); +legend('VRPN','IMU', 'Model', 'location', 'northwest'); + linkaxes([ax1, ax2], 'x'); %% Plot VRPN Position -figure(9); ax1 = subplot(3, 1, 1); +figure(10); ax1 = subplot(3, 1, 1); stairs(time, x_pos_raw, '.-'); hold on; grid minor; -%stairs(time_model_40ms, x_position_model_data, '.-'); +stairs(time_model_40ms, x_position_model_data, '.-'); stairs(time, x_setpoint, '.-'); title('X position'); xlabel('Time (s)'); @@ -255,7 +232,7 @@ legend('X position', 'X position model', 'X setpoint'); ax2 = subplot(3, 1, 2); stairs(time, y_pos_raw, '.-'); hold on; grid minor; -%stairs(time_model_40ms, y_position_model_data, '.-'); +stairs(time_model_40ms, y_position_model_data, '.-'); stairs(time, y_setpoint, '.-'); title('Y position'); xlabel('Time (s)'); @@ -265,10 +242,11 @@ legend('Y position', 'Y position model', 'Y setpoint'); ax3 = subplot(3, 1, 3); stairs(time, z_pos_raw, '.-'); hold on; grid minor; stairs(time_model_40ms, z_position_model_data, '.-'); +stairs(time, z_setpoint, '.-'); title('Z position'); xlabel('Time (s)'); ylabel('Z position'); -legend('Z position', 'Z position model', 'Y setpoint'); +legend('Z position', 'Z position model', 'Z setpoint'); linkaxes([ax1, ax2, ax3], 'x'); diff --git a/controls/model/modelParameters.m b/controls/model/modelParameters.m index 0b7971269fcd3f3bef9de1f2b0e2f69a8a83d203..9a0694366b23315e7dd7c7d36f4e6be5d3c3b01a 100644 --- a/controls/model/modelParameters.m +++ b/controls/model/modelParameters.m @@ -1,9 +1,16 @@ +% Add Library Blocks to Path + path = genpath('Library_blocks'); + addpath(path); + % Log Analysis Toggle - logAnalysisToggle = 1; % 1 for log analysis, 0 for normal operation + logAnalysisToggle = 0; % 1 for log analysis, 0 for normal operation + +% Physics Verification Toggle + physicsVerificationToggle = 1; % Define Simulink Runtime (if logAnalysisToggle is selected, this will be % automatically set based on the log files time) - runtime = 20; + runtime = 55; % Model Parameters m = 1.216; % Quadrotor + battery mass @@ -13,7 +20,7 @@ Jzz = 0.0285; % Quadrotor and battery motor of inertia around bz (yaw) Jreq = 4.2012e-05; % Rotor and motor moment of inertia around axis of rotation Kt = 1.2007e-05; % Rotor thrust constant - Kh = 0; % Rotor in-plane drag constant + Kh = 3.4574e-04; % Rotor in-plane drag constant Kd = 1.4852e-07; % Rotor drag constant rhx = 0.16; % X-axis distance from center of mass to a rotor hub rhy = 0.16; % Y-axis distance from center of mass to a rotor hub @@ -23,17 +30,18 @@ Kq = 96.3422; % Motor torque constant Kv = 96.3422; % Motor back emf constant If = 0.3836; % Motor internal friction current - Pmin = 0; % Minimum zybo output duty cycle command - Pmax = 1; % Maximum zybo output duty cycle command + Pmin = 0; % Minimum zybo output duty cycle command + Pmax = 1; % Maximum zybo output duty cycle command Tc = 0.04; % Camera system sampling period Tq = 0.005; % Quad sampling period tau_c = 0; % Camera system total latency - Vb = 11.4; % Nominal battery voltage (V) + Vb = 12.3; % Nominal battery voltage (V) x_controlled_o = 0; % Equilibrium lateral controller output y_controlled_o = 0; % Equilibrium longitudinal controller output yaw_controlled_o = 0; % Equilibrium yaw controller output Kp_mahony = 0.4; % Proportional term for mahony filter Ki_mahony = 0.001; % Integral term for mahony filter + delta_T = 4 * [ 0, 0, 2.351e-4 ]; % Define Biquad Filter Parameters b0 = 0.020083; @@ -103,9 +111,9 @@ if logAnalysisToggle == 1 time = dataStruct.Time.data; time = time - time(1); time_indices = length(time); - + runtime = max(time); - + % Determine x position error x_setpoint = dataStruct.X_Setpoint_Constant.data; x_pos_raw = dataStruct.VRPN_X_Constant.data; @@ -137,20 +145,20 @@ if logAnalysisToggle == 1 y_vel = timeseries(y_vel_raw, time); % Determine pitch error - pitch_setpoint = dataStruct.X_pos_PID_Correction.data; + pitch_setpoint = dataStruct.X_Vel_PID_Correction.data; pitch_angle_raw = dataStruct.Pitch_trim_add_Sum.data; pitch_error = timeseries(pitch_setpoint - pitch_angle_raw, time); pitch_angle = timeseries(pitch_angle_raw, time); % Determine roll error - roll_setpoint = dataStruct.Y_pos_PID_Correction.data; + roll_setpoint = dataStruct.Y_Vel_PID_Correction.data; roll_angle_raw = dataStruct.Roll_Constant.data; roll_error = timeseries(roll_setpoint - roll_angle_raw, time); roll_angle = timeseries(roll_angle_raw, time); % Determine yaw error - yaw_setpoint = zeros(length(time), 1); % NEEDS UPDATED WHEN LOG FILE INCLUDES YAW SETPOINT - yaw_angle_raw = zeros(length(time), 1); % NEEDS UPDATED WHEN LOG FILE INCLUDES YAW VALUE + yaw_setpoint = dataStruct.Yaw_Setpoint_Constant.data; + yaw_angle_raw = dataStruct.Yaw_Constant.data; yaw_error = timeseries(yaw_setpoint - yaw_angle_raw, time); yaw_angle = timeseries(yaw_angle_raw, time); @@ -205,7 +213,6 @@ if logAnalysisToggle == 1 % Create time series object for z command throttle_command = timeseries(dataStruct.RC_Throttle_Constant.data, time); - %z_command = dataStruct.RC_Throttle_Constant.data; % Pull the measurements from the complimentary filter pitch_measured_IMU = dataStruct.Pitch_trim_add_Sum.data; @@ -218,37 +225,134 @@ if logAnalysisToggle == 1 pitch_measured_VRPN = dataStruct.VRPN_Pitch_Constant.data; roll_measured_VRPN = dataStruct.VRPN_Roll_Constant.data; -% Set height_controlled_o to initial throttle command -% height_controlled_o = dataStruct.RC_Throttle_Constant.data(1); -% -% Set rotor speed initial conditions to there calculated values based on -% initial throttle control -% omega0_o = (sqrt(((height_controlled_o ... -% - Pmin)/(Pmax - Pmin)* Vb - Rm * If) * 4 * ... -% Rm * Kv^2 * Kq * Kd + 1) - 1) / (2 * Rm * ... -% Kv * Kq * Kd); -% omega1_o = omega0_o; -% omega2_o = omega0_o; -% omega3_o = omega0_o; -% -% Set initial positions -% x_o = x_position(1); -% y_o = y_position(1); -% z_o = z_position(1); -% -% Set initial velocities -% x_vel_o = (x_position(1) - x_position(2))/(time(1) - time(2)); -% y_vel_o = (y_position(1) - y_position(2))/(time(1) - time(2)); -% z_vel_o = (z_position(1) - z_position(2))/(time(1) - time(2)); -% -% Equilibrium angles -% roll_o = roll_measured_VRPN(1); -% pitch_o = pitch_measured_VRPN(1); -% yaw_o = 0; -% -% Equilibrium angular rates -% rollrate_o = (roll_measured_VRPN(1) - roll_measured_VRPN(2))/(time(1) - time(2)); -% pitchrate_o = (pitch_measured_VRPN(1) - pitch_measured_VRPN(2))/(time(1) - time(2)); -% yawrate_o = 0; + % Define setpoint timeseries + x_setpoint_model = timeseries(x_setpoint, time); + y_setpoint_model = timeseries(y_setpoint, time); + z_setpoint_model = timeseries(z_setpoint, time); +end + +if physicsVerificationToggle == 1 + % PHYSICAL SYSTEM PARAMETERS + +% quadrotor + battery mass +m = 1.216; +% quadrotor + battery inertia tensor +J = diag([ 0.0130 0.0140 0.0285 ]); +% quadrotor + battery body frame origin to c.o.g. error radius +r_oc = [ 0 ; 0 ; 0 ]; + +% mass of rigidly attached load +m_L = 0; +% dimensions of assuemd rectangular load +x_L = 0; y_L = 0; z_L = 0; +x_L = 0; y_L = 0; z_L = 0; +% inertia tensor of load +J_L = m_L/12*diag([y_L^2+z_L^2,x_L^2+z_L^2,x_L^2+y_L^2]); +% location of load center of mass in body frame +r_oL = [0; 0; 0];%[ 0.12 ; 0.12 ; -0.04];%(0.04 + z_L/2) ]; +%r_oL = [ .115 ; .115 ; 0.04]; + +% acceleration of gravity +g = 9.81; + +% initial dynamics states conditions +u0 = 0; +v0 = 0; +w0 = 0; +p0 = 0; +q0 = 0; +r0 = 0; +x0 = 0; +y0 = 0; +z0 = 0; +phi0 = 0; +theta0 = 0; +psi0 = 0; + +% ROTOR PARAMETERS + +% nominally equal rotor parameters +K_T = cell(1,4); K_H = cell(1,4); K_d = cell(1,4); +Delta_T = cell(1,4); +%Delta_T = [0 0 0]; +J_r = cell(1,4); Gamma_H = cell(1,4); +for i = 1:4 + % rotor thrust constants + K_T{i} = 1.2007e-05; + % rotor H-force coefficeint + K_H{i} = 3.4574e-04; + % rotor drag constant + K_d{i} = 1.4852e-07; + % rotor b_z axis velocity thrust adjustment factor + Delta_T{i} = 0.5*[ 0 0 2.351e-4 ]; + % equivalent rotor + motor moment of inertia + J_r{i} = 4.2012e-05; + % h-force xy-plane selection matrix + Gamma_H{i} = [ 1 0 0 ; 0 1 0 ; 0 0 0 ]; +end + + + +% ESC-MOTOR PARAMETERS +have_motor_transient = 1; +% nominally equal motor and eletronic speed control parameters +R_m = cell(1,4); K_Q = cell(1,4); K_V = cell(1,4); +i_0 = cell(1,4); omega_0 = cell(1,4); K_E = cell(1,4); +p_0 = cell(1,4); p_max = cell(1,4); +for i = 1:4 + % motor resistance + R_m{i} = 0.235; + % motor torque constant + K_Q{i} = 96.3422; + % motor back-emf constant + K_V{i} = 96.3422; + % motor no-load current + i_0{i} = 0.3836; + % initial motor/rotor speed + omega_0{i} = (m*g/4/K_T{1})^0.5; + % ESC normalized pwm input factor + K_E{i} = 1; + % ESC turn-on duty cycle + p_0{i} = 0; + % ESC maximum duty cycle (as calibrated) + p_max{i} = 1; +end + + + +% ROTOR LOCATION/ORIENTATION PARAMETERS + +% locatin of hub 1 in body frame +r_h{1} = [ rhx ; rhy ; -rhz ]; +% rotor 1 thrust unit vector +Gamma_T{1} = [ 0 ; 0 ; -1 ]; +% rotor 1 rotation unit vector +Gamma_Omega{1} = [ 0 ; 0 ; -1 ]; + +r_h{2} = [ -rhx ; rhy ; -rhz ]; +Gamma_T{2} = [ 0 ; 0 ; -1 ]; +Gamma_Omega{2} = [ 0 ; 0 ; 1 ]; + +r_h{3} = [ -rhx ; -rhy ; -rhz ]; +Gamma_T{3} = [ 0 ; 0 ; -1 ]; +Gamma_Omega{3} = [ 0 ; 0 ; -1 ]; + +r_h{4} = [ rhx ; -rhy ; -rhz ]; +Gamma_T{4} = [ 0 ; 0 ; -1 ]; +Gamma_Omega{4} = [ 0 ; 0 ; 1 ]; + + + +% BATTERY PARAMETERS + +% starting/operating battery voltage +V_0 = 11.4; %12.4; %11.4; +% approximate hovering rate of battery discharge +d_V = 0; + +% DISTURBANCE PARAMETERS + +F_D = 1*randn(3,1); +Q_D = 0.05*randn(3,1); end \ No newline at end of file diff --git a/controls/model/test_model.slx b/controls/model/test_model.slx index d5bc5cf9bf30f0bb5a79b4167ac79bdb8b1be8a8..35a8b396d018cd92f55e5327af5b488dbafddcaf 100644 Binary files a/controls/model/test_model.slx and b/controls/model/test_model.slx differ diff --git a/groundStation/gui/MicroCART/MicroCART.pro.user b/groundStation/gui/MicroCART/MicroCART.pro.user index b845d25d848e878796105144c4340687885425fb..f36c56fc6c5e8e57f31920dd005d4aca3d16ec64 100644 --- a/groundStation/gui/MicroCART/MicroCART.pro.user +++ b/groundStation/gui/MicroCART/MicroCART.pro.user @@ -1,10 +1,10 @@ <?xml version="1.0" encoding="UTF-8"?> <!DOCTYPE QtCreatorProject> -<!-- Written by QtCreator 4.0.1, 2017-04-11T17:47:13. --> +<!-- Written by QtCreator 4.1.0, 2017-04-19T23:57:31. --> <qtcreator> <data> <variable>EnvironmentId</variable> - <value type="QByteArray">{ec588c71-c0cc-43f4-8233-a07fa24de8ad}</value> + <value type="QByteArray">{f7736f41-610d-4989-a7d9-6e994afe94ba}</value> </data> <data> <variable>ProjectExplorer.Project.ActiveTarget</variable> @@ -61,72 +61,12 @@ <valuemap type="QVariantMap"> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{c6f8ca21-0eb9-4188-b2e8-fae8725afa1b}</value> + <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{94de1029-defb-4d1d-a0ac-6d51aba06ea3}</value> <value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value> <value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value> <value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value> <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0"> - <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/jake/Microcart_17-18/groundStation/gui/build-MicroCART-Desktop-Debug</value> - <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0"> - <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0"> - <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value> - <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value> - <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value> - <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value> - <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value> - <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value> - </valuemap> - <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1"> - <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value> - <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments"> - <value type="QString">-w</value> - <value type="QString">-r</value> - </valuelist> - <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value> - <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value> - <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value> - </valuemap> - <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value> - </valuemap> - <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1"> - <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0"> - <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value> - <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments"> - <value type="QString">-w</value> - <value type="QString">-r</value> - </valuelist> - <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value> - <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value> - <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value> - </valuemap> - <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value> - </valuemap> - <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value> - <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value> - <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Debug</value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value> - <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">2</value> - <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value> - </valuemap> - <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.1"> - <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/jake/Microcart_17-18/groundStation/gui/build-MicroCART-Desktop-Release</value> + <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory"></value> <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0"> <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0"> <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value> @@ -185,7 +125,7 @@ <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value> <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value> </valuemap> - <value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">2</value> + <value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">1</value> <valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0"> <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0"> <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value> @@ -244,13 +184,13 @@ <valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">MicroCART</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value> - <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/home/jake/Microcart_17-18/groundStation/gui/MicroCART/MicroCART.pro</value> + <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/local/ucart/Documents/MicroCART_17-18/groundStation/gui/MicroCART/MicroCART.pro</value> <value type="bool" key="QmakeProjectManager.QmakeRunConfiguration.UseLibrarySearchPath">true</value> <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.CommandLineArguments"></value> <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.ProFile">MicroCART.pro</value> <value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseDyldImageSuffix">false</value> <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory"></value> - <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory.default">/home/jake/Microcart_17-18/groundStation/gui/build-MicroCART-Desktop-Debug</value> + <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory.default">/local/ucart/Documents/MicroCART_17-18/groundStation/gui/MicroCART</value> <value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value> <value type="bool" key="RunConfiguration.UseCppDebugger">false</value> <value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value> diff --git a/groundStation/gui/MicroCART/mainwindow.cpp b/groundStation/gui/MicroCART/mainwindow.cpp index 22df6f238dd90b4a8764dbab5bdbfc1da82cec30..daed528e84e331e8d384b84b642492a66a6a8bae 100644 --- a/groundStation/gui/MicroCART/mainwindow.cpp +++ b/groundStation/gui/MicroCART/mainwindow.cpp @@ -28,8 +28,8 @@ MainWindow::MainWindow(QWidget *parent) : ui->setupUi(this); QGraphicsScene *topScene = new QGraphicsScene(this); - QuadItem * quad = new QuadItem(); ui->topView->setScene(topScene); + QuadItem * quad = new QuadItem(); topScene->addItem(quad); @@ -51,7 +51,7 @@ MainWindow::MainWindow(QWidget *parent) : this, SLOT (updateTracker(float, float, float, float, float, float))); connect(trackerWorker, SIGNAL (finished(float, float, float, float, float, float)), - quad, SLOT (quad->updateQuad(float, float, float, float, float, float))); + quad, SLOT(updateQuad(float,float,float,float,float,float))); /* Create another worker for the control graph */ QThread * cwThread = new QThread(this); @@ -112,13 +112,6 @@ MainWindow::~MainWindow() void MainWindow::updateConsole() { if (backendPipe != -1) { - char buf[256]; - size_t len = 0; - len = readBackend(backendPipe, buf, len); - if (len > 0) { - QLineEdit * con = ui->vConsole; - con->setText(con->text().append(buf)); - } } } @@ -402,3 +395,8 @@ void MainWindow::on_pbLoadWaypoints_clicked() f.close(); } } + +void MainWindow::on_socketPath_returnPressed() +{ + QProcessEnvironment::systemEnvironment().insert("UCART_SOCKET", ui->socketPath->text()); +} diff --git a/groundStation/gui/MicroCART/mainwindow.h b/groundStation/gui/MicroCART/mainwindow.h index de7b2a32dc5e3ec0f0099403a676644a0fa8666a..62b0443047c1fab4a612573f8d90f4ee1e150cda 100644 --- a/groundStation/gui/MicroCART/mainwindow.h +++ b/groundStation/gui/MicroCART/mainwindow.h @@ -71,6 +71,8 @@ private slots: void on_pbLoadWaypoints_clicked(); + void on_socketPath_returnPressed(); + private: Ui::MainWindow *ui; pid_t backendPid; diff --git a/groundStation/gui/MicroCART/mainwindow.ui b/groundStation/gui/MicroCART/mainwindow.ui index 16c1d1a5e6a135a79cabc2af4735569d2cb5b4f8..a6795802eddc4c1dc1e89b03f408fb82bb30762b 100644 --- a/groundStation/gui/MicroCART/mainwindow.ui +++ b/groundStation/gui/MicroCART/mainwindow.ui @@ -18,7 +18,7 @@ <item> <widget class="QTabWidget" name="tabWidget"> <property name="currentIndex"> - <number>2</number> + <number>0</number> </property> <widget class="QWidget" name="backend"> <attribute name="title"> @@ -37,7 +37,10 @@ <item row="0" column="1"> <widget class="QLineEdit" name="socketPath"> <property name="enabled"> - <bool>false</bool> + <bool>true</bool> + </property> + <property name="text"> + <string/> </property> </widget> </item> @@ -151,8 +154,8 @@ <rect> <x>0</x> <y>0</y> - <width>962</width> - <height>660</height> + <width>98</width> + <height>76</height> </rect> </property> <layout class="QVBoxLayout" name="verticalLayout_8"> @@ -804,8 +807,8 @@ </property> </widget> </item> - <item row="1" column="1"> - <widget class="QLineEdit" name="autonavDelay"> + <item row="0" column="1"> + <widget class="QLineEdit" name="autonavThreshold"> <property name="sizePolicy"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <horstretch>0</horstretch> @@ -813,12 +816,12 @@ </sizepolicy> </property> <property name="text"> - <string>1500</string> + <string>0.1</string> </property> </widget> </item> - <item row="0" column="1"> - <widget class="QLineEdit" name="autonavThreshold"> + <item row="1" column="1"> + <widget class="QLineEdit" name="autonavDelay"> <property name="sizePolicy"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <horstretch>0</horstretch> @@ -826,7 +829,7 @@ </sizepolicy> </property> <property name="text"> - <string>0.05</string> + <string>88</string> </property> </widget> </item> diff --git a/groundStation/gui/MicroCART/quaditem.cpp b/groundStation/gui/MicroCART/quaditem.cpp index b43ced998e8720bf1cb7d50823a6bc8f39b3bef5..55e1413af0ea2a562b9ec2a61c280e4afb02958a 100644 --- a/groundStation/gui/MicroCART/quaditem.cpp +++ b/groundStation/gui/MicroCART/quaditem.cpp @@ -1,6 +1,7 @@ #include "quaditem.h" #include <QPixmap> #include <QLabel> +#include <QtMath> QuadItem::QuadItem() { @@ -20,13 +21,12 @@ void QuadItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, void QuadItem::updateQuad(float longitudinal, float lateral, float height, float pitch, float roll, float yaw) { - this->setPos(longitudinal*10, lateral*10); - - QPointF center = boundingRect().center(); - QTransform trans = this->transform(); - trans.translate(center.x(), center.y()); - trans.rotate(yaw); - trans.translate(-center.x(), -center.y()); - this->setTransform(trans); + QPointF center = boundingRect().center(); + this->setTransform(QTransform().translate(center.x(), center.y()).rotate(qRadiansToDegrees(yaw)).translate(-center.x(), -center.y())); + this->setPos(longitudinal*100, lateral*100); +// QTransform trans = this->transform(); +// trans.translate(center.x(), center.y()); +// trans.translate(-center.x(), -center.y()); +// this->setTransform(trans); update(); } diff --git a/groundStation/gui/MicroCART/quaditem.h b/groundStation/gui/MicroCART/quaditem.h index 0688802193e5e88b83c3507f48c7674b69d2434e..3f271806b2503a0a98d1284b5cbbc9520436e03e 100644 --- a/groundStation/gui/MicroCART/quaditem.h +++ b/groundStation/gui/MicroCART/quaditem.h @@ -17,7 +17,7 @@ public: QRectF boundingRect() const; void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); -private slots: +public slots: void updateQuad(float longitudinal, float lateral, float height, float pitch, float roll, float yaw); }; diff --git a/groundStation/gui/MicroCART/trackerworker.cpp b/groundStation/gui/MicroCART/trackerworker.cpp index 9a6830a7755f635ae15428fa4686c8a7f44abec1..13d9c15bccb202ee101886e8a7adb298f1f7da5f 100644 --- a/groundStation/gui/MicroCART/trackerworker.cpp +++ b/groundStation/gui/MicroCART/trackerworker.cpp @@ -2,6 +2,7 @@ #include <QThread> #include "frontend_common.h" #include "frontend_tracker.h" +#include "quaditem.h" TrackerWorker::TrackerWorker() : QObject(), conn(NULL) diff --git a/groundStation/scripts/take_off.sh b/groundStation/scripts/take_off.sh index 167bd866daa757cb7f4f0b442c29c1f1eb3bc39e..649f5499bf4a51c493f416231e25a8351f2c3555 100755 --- a/groundStation/scripts/take_off.sh +++ b/groundStation/scripts/take_off.sh @@ -10,7 +10,7 @@ sleep 2 ./setsource "T trim add" "summand 1" "Altitude PID" "Correction" #./setsource 14 0 8 0 -./setparam "Throttle trim" 0 0.45 +./setparam "Throttle trim" 0 0.5 #./setparam 13 0 0.45 ./setparam "Alt Setpoint" 0 -0.88 #./setparam 11 0 -0.5 diff --git a/groundStation/scripts/touch_down.sh b/groundStation/scripts/touch_down.sh index 3bfb41533c077cfd5b998d59a62615bd24b53fa7..79a4bc11dc49dce027e4438eae05aa819b512c78 100755 --- a/groundStation/scripts/touch_down.sh +++ b/groundStation/scripts/touch_down.sh @@ -1,6 +1,6 @@ #! /bin/bash -cut_off="-0.25" +cut_off="-0.15" regex='[+-]?[0-9]+\.?[0-9]*$' @@ -8,9 +8,13 @@ regex='[+-]?[0-9]+\.?[0-9]*$' alt="$(echo "$(./getparam 'VRPN Alt' 0)" | grep -Eo "$regex")" while awk 'BEGIN { if ('$alt'>='$cut_off') {exit 1}}'; do - alt="$(echo "$(./getparam 'VRPN Alt' 0)" | grep -Eo "$regex")" - ./setparam 'Alt Setpoint' 0 $( bc <<< "$alt + 0.1") - echo "$alt too high" + if (( $(bc <<< "$alt < -0.5") )); then + alt="$(echo "$(./getparam 'VRPN Alt' 0)" | grep -Eo "$regex")" + ./setparam 'Alt Setpoint' 0 $( bc <<< "$alt + 0.15") + else + alt="$(echo "$(./getparam 'VRPN Alt' 0)" | grep -Eo "$regex")" + ./setparam 'Alt Setpoint' 0 $( bc <<< "$alt + 0.25") + fi sleep .5 done diff --git a/groundStation/src/backend/backend.c b/groundStation/src/backend/backend.c index 3819ebc538b4ea2c4b9e76ab86b4009eeb828dac..f384a6a1a96f59985fabe29fa4a431678727b31a 100644 --- a/groundStation/src/backend/backend.c +++ b/groundStation/src/backend/backend.c @@ -844,10 +844,13 @@ static void quad_recv() { memmove(respBuf, respBuf + packetlen, respBufLen - packetlen); respBufLen -= packetlen; + char * debug_string; switch (m.msg_type) { - case DEBUG_ID: + case DEBUG_ID: /* in case of debug. Quad send null terminated string in data */ - printf(" (Quad) : %s\n", data); + debug_string = strndup((char *)data, m.data_len); + printf(" (Quad) : %s\n", debug_string); + free(debug_string); break; case LOG_ID: if (!quadlog_file_open) { diff --git a/quad/Makefile b/quad/Makefile index b6838e4bfdc801ae4c8401f8c06eb5941e706557..0a92c686ac1fd60dc693dbc0a8f0c86f0768331a 100644 --- a/quad/Makefile +++ b/quad/Makefile @@ -39,8 +39,8 @@ test: all $(MAKE) -C src/computation_graph test $(MAKE) -C src/quad_app test ruby scripts/tests/test_safety_checks.rb - # ruby scripts/tests/test_unix_uart.rb - # ruby scripts/tests/run_virtual_test_flight.rb + ruby scripts/tests/test_memory_integrity.rb + ruby scripts/tests/test_communication.rb clean: rm -rf $(INCDIR) $(LIBDIR) $(OUTDIR) $(EXEDIR) diff --git a/quad/scripts/tests/test_unix_uart.rb b/quad/scripts/tests/test_communication.rb similarity index 50% rename from quad/scripts/tests/test_unix_uart.rb rename to quad/scripts/tests/test_communication.rb index 1c9b6a82e4fb3c84ded4038e666378c8b4a5016f..8797cc16dabab068acafe493cdc1b2dfab824ddd 100644 --- a/quad/scripts/tests/test_unix_uart.rb +++ b/quad/scripts/tests/test_communication.rb @@ -11,19 +11,29 @@ require script_dir + "/testing_library" bin_dir = script_dir + "/../../bin/" Dir.chdir(bin_dir) - Timeout::timeout(30) { puts("Setting up...") - sleep 1 - # Start virtual quad - quad_pid = Process.spawn("./virt-quad -q", + quad_pid = Process.spawn("./virt-quad start -q", { :rlimit_as => 536870912, # 512 MiB total RAM :rlimit_stack => 1048576}) # 1 MiB stack - delay_spin_cursor(5) + sleep 0.5 + + # Set RC switches + set_gear GEAR_OFF + set_flap FLAP_OFF + + # Set initial quad orientation (flat on the ground, facing forward) + `./virt-quad set i2c_imu_x 0` + `./virt-quad set i2c_imu_y 0` + `./virt-quad set i2c_imu_z -1` + `./virt-quad set rc_roll 0.498` + `./virt-quad set rc_pitch 0.497` + `./virt-quad set rc_yaw 0.498` + ################# # Begin Tests @@ -31,39 +41,46 @@ Timeout::timeout(30) { begin - puts("Beginning tests...") - - # Flip gear on - File.write(GEAR, GEAR_ON) - sleep 0.015 + puts "------------------------------------------" + puts "-- Beginning basic communication test..." + puts "------------------------------------------" for j in 1..10 + # Send a debug command - File.write(UART_RX, [0xBE, 1, 0, 0, 0, 0, 0, 0xBF].pack("CCCCCCCC")) + Thread.new { + sleep 0.5 + send_packet [0xBE, 1, 0, 0, 0, 0, 0, 0xBF] + } fifo = File.open(UART_TX) # Receive the header msg = [] for i in 1..7 - sleep 0.010 - msg.push(fifo.read(1)) + sleep 0.01 + c = fifo.read(1) + msg.push(c) end # Receive the remaining data, according to the header specified length length = msg[5..7].join().unpack("S")[0] + msg = [] for i in 1..length - sleep 0.010 - msg.push(fifo.read(1)) + sleep 0.01 + c = fifo.read(1) + msg.push(c) end fifo.close - puts msg.join() - assert_equal(msg.join().force_encoding("UTF-8"), "Packets received: #{j}") + msg = msg.join() + puts msg + assert_equal(msg.force_encoding("UTF-8"), "Packets received: #{j}") end - puts "Basic UART test passed." + puts "Basic communication test passed." + puts "------------------------------------------" ensure diff --git a/quad/scripts/tests/test_logging.rb b/quad/scripts/tests/test_logging.rb new file mode 100644 index 0000000000000000000000000000000000000000..58d16f73caa7837e2b9aa82dfa48e0e7bbb257d4 --- /dev/null +++ b/quad/scripts/tests/test_logging.rb @@ -0,0 +1,117 @@ +#!/usr/bin/env ruby + +# Logging test +# +# Let the quad fly for a bit, and then ensure we can +# get its logs + +script_dir = File.expand_path(File.dirname(__FILE__)) +require script_dir + "/testing_library" + +bin_dir = script_dir + "/../../bin/" +Dir.chdir(bin_dir) + +Timeout::timeout(30) { + + puts("Setting up...") + + # Start virtual quad + quad_pid = Process.spawn("./virt-quad start -q", + { :rlimit_as => 536870912, # 512 MiB total RAM + :rlimit_stack => 1048576}) # 1 MiB stack + + sleep 0.5 + + # Set RC switches + set_gear GEAR_OFF + set_flap FLAP_OFF + + # Set initial quad orientation (flat on the ground, facing forward) + `./virt-quad set i2c_imu_x 0` + `./virt-quad set i2c_imu_y 0` + `./virt-quad set i2c_imu_z -1` + `./virt-quad set rc_roll 0.498` + `./virt-quad set rc_pitch 0.497` + `./virt-quad set rc_yaw 0.498` + + + ################# + # Begin Tests + ################# + + begin + + puts "------------------------------------------" + puts "-- Beginning logging test..." + puts "------------------------------------------" + + # Set initial quad orientation (flat on ground, facing forward) + `./virt-quad set i2c_imu_x 0` + `./virt-quad set i2c_imu_y 0` + `./virt-quad set i2c_imu_z -1` + `./virt-quad set rc_roll 0.498` + `./virt-quad set rc_pitch 0.497` + `./virt-quad set rc_yaw 0.498` + + puts("Turning on GEAR...") + set_gear GEAR_ON + set_flap FLAP_ON + sleep 0.015 + + puts("Increasing Thrust to half maximum...") + for i in (THROTTLE_MIN..THROTTLE_MID).step(0.01) + set_throttle(i) + sleep 0.005 + end + + puts("Hovering for 3 seconds") + sleep 3 + + puts("Switching to autonomous and hovering for 3 seconds") + set_flap FLAP_OFF + sleep 3 + + puts("Switch back to manual, relaxing thrust to zero") + set_flap FLAP_ON + i = THROTTLE_MID + while i > THROTTLE_MIN + i -= 0.01 + set_throttle(i) + sleep 0.005 + end + + # Get logs + + Thread.new { + sleep 1 + puts("Swiching off GEAR...") + set_gear GEAR_OFF + } + + logs = [] + + begin + while true + logs.push(recv_packet) + end + rescue Timeout::Error + puts "No logs left" + end + + if logs.length == 2 + log_data = logs[1].split("\n") + for data in log_data + puts data + end + p log_data.length + end + + puts "------------------------------------------" + + ensure + + Process.kill(9, quad_pid) + Process.wait(quad_pid) + + end +} diff --git a/quad/scripts/tests/test_memory_integrity.rb b/quad/scripts/tests/test_memory_integrity.rb new file mode 100644 index 0000000000000000000000000000000000000000..adb8f9190b6adb3fff8a6e6f8de2eb143854cfe3 --- /dev/null +++ b/quad/scripts/tests/test_memory_integrity.rb @@ -0,0 +1,95 @@ +#!/usr/bin/env ruby + +# Test Flight +# +# A simple virtual test flight (take off, hover, and set back down) +# with valgrind, in order to detect memory leaks + +script_dir = File.expand_path(File.dirname(__FILE__)) +require script_dir + "/testing_library" + +bin_dir = script_dir + "/../../bin/" +Dir.chdir(bin_dir) + +puts("Firing up the quad...") + +# Start virtual quad +quad = Process.spawn("valgrind --leak-check=full --log-file=./valgrind.out ./virt-quad start") + +sleep 1.5 + +set_gear GEAR_OFF +set_flap FLAP_ON + +################## +# Begin Flight! +################## + +begin + puts "------------------------------------------" + puts "-- Beginning memory integrity test..." + puts "------------------------------------------" + + # Set initial quad orientation (flat on ground, facing forward) + `./virt-quad set i2c_imu_x 0` + `./virt-quad set i2c_imu_y 0` + `./virt-quad set i2c_imu_z -1` + `./virt-quad set rc_roll 0.498` + `./virt-quad set rc_pitch 0.497` + `./virt-quad set rc_yaw 0.498` + + puts("Turning on GEAR...") + set_gear GEAR_ON + sleep 0.015 + + puts("Increasing Thrust to half maximum...") + for i in (THROTTLE_MIN..THROTTLE_MID).step(0.01) + set_throttle(i) + sleep 0.005 + end + + puts("Hovering for 3 seconds") + sleep 3 + + puts("Switching to autonomous and hovering for 3 seconds") + set_flap FLAP_OFF + sleep 3 + + puts("Switch back to manual, relaxing thrust to zero") + set_flap FLAP_ON + i = THROTTLE_MID + while i > THROTTLE_MIN + i -= 0.01 + set_throttle(i) + sleep 0.005 + end + + puts("Swiching off GEAR...") + set_gear GEAR_OFF + + sleep 3 + + set_throttle THROTTLE_MIN + + puts("Flight ended successfully."); +ensure + + Process.kill(2, quad) + sleep 1 # wait for valgrind to write to file + + # Process the valgrind file + file = File.open("./valgrind.out") + everything = file.readlines + last_line = everything.last + errors = last_line.scanf("%s ERROR SUMMARY: %d errors %s") + puts everything + if errors[1] > 0 + puts "Memory Integrity Check Failed." + puts "------------------------------------------" + Kernel.exit(1) + end + + puts "Memory Integrity Check Passed." + puts "------------------------------------------" +end + diff --git a/quad/scripts/tests/test_safety_checks.rb b/quad/scripts/tests/test_safety_checks.rb index 20c49fb33a75780419aa360794e8d3a757473766..c96a8228f66cde705e62e81ab992eabd803c2569 100644 --- a/quad/scripts/tests/test_safety_checks.rb +++ b/quad/scripts/tests/test_safety_checks.rb @@ -17,11 +17,11 @@ Timeout::timeout(60) { puts("Setting up...") # Start virtual quad - quad_pid = Process.spawn("./virt-quad -q", + quad_pid = Process.spawn("./virt-quad start -q", { :rlimit_as => 536870912, # 512 MiB total RAM :rlimit_stack => 1048576}) # 1 MiB stack - delay_spin_cursor(1) + sleep 0.5 # Set RC switches set_gear GEAR_OFF @@ -40,7 +40,9 @@ Timeout::timeout(60) { ################# begin - puts("Beginning tests...") + puts "------------------------------------------" + puts "-- Beginning safety checks test..." + puts "------------------------------------------" puts("Check that motors are off at startup") check_motors_are_off "Motors weren't off at startup! How dangerous!" @@ -83,18 +85,14 @@ Timeout::timeout(60) { puts("Check that motors turn on") set_throttle THROTTLE_MID - spinner = Thread.new { delay_spin_cursor(5) } - motors = get_motor_averages(100, 3) - spinner.exit + motors = get_motor_averages(100, 2) p motors motors.each { |value| assert_operator(value, :>, THROTTLE_QUAR) } puts("Check that when quad is tilted, motors respond correctly") puts("Tilting forwards...") `./virt-quad set i2c_imu_x 0.25` - spinner = Thread.new { delay_spin_cursor(5) } - motors = get_motor_averages(100, 3) - spinner.exit + motors = get_motor_averages(100, 2) p motors assert_operator(motors[0], :>, motors[1]) assert_operator(motors[0], :>, motors[3]) @@ -102,9 +100,7 @@ Timeout::timeout(60) { assert_operator(motors[2], :>, motors[3]) puts("Tilting backwards...") `./virt-quad set i2c_imu_x -0.25` - spinner = Thread.new { delay_spin_cursor(5) } - motors = get_motor_averages(100, 3) - spinner.exit + motors = get_motor_averages(100, 2) p motors assert_operator(motors[0], :<, motors[1]) assert_operator(motors[0], :<, motors[3]) @@ -113,9 +109,7 @@ Timeout::timeout(60) { puts("Tilting right...") `./virt-quad set i2c_imu_x 0` `./virt-quad set i2c_imu_y 0.25` - spinner = Thread.new { delay_spin_cursor(5) } - motors = get_motor_averages(100, 3) - spinner.exit + motors = get_motor_averages(100, 2) p motors assert_operator(motors[0], :<, motors[2]) assert_operator(motors[0], :<, motors[3]) @@ -123,9 +117,7 @@ Timeout::timeout(60) { assert_operator(motors[1], :<, motors[3]) puts("Tilting left...") `./virt-quad set i2c_imu_y -0.25` - spinner = Thread.new { delay_spin_cursor(5) } - motors = get_motor_averages(100, 3) - spinner.exit + motors = get_motor_averages(100, 2) p motors assert_operator(motors[0], :>, motors[2]) assert_operator(motors[0], :>, motors[3]) @@ -141,6 +133,7 @@ Timeout::timeout(60) { set_throttle THROTTLE_MIN puts "All safety checks passed." + puts "------------------------------------------" ensure diff --git a/quad/scripts/tests/testing_library.rb b/quad/scripts/tests/testing_library.rb index 6301d840d821f51356b1df742f7a1490fff98fb5..aad1ba85660bc1f2d2a9e50dfbeacc4a8243e08e 100644 --- a/quad/scripts/tests/testing_library.rb +++ b/quad/scripts/tests/testing_library.rb @@ -13,26 +13,13 @@ FLAP_ON = 0.9 FLAP_OFF = 0.1 GRAVITY = 4096 -MOTOR1 = "virt-quad-fifos/motor1" -MOTOR2 = "virt-quad-fifos/motor2" -MOTOR3 = "virt-quad-fifos/motor3" -MOTOR4 = "virt-quad-fifos/motor4" - -GEAR = "virt-quad-fifos/rc-gear" -THROTTLE = "virt-quad-fifos/rc-throttle" - -LED = "virt-quad-fifos/mio7-led" - -I2C_MPU_ACCEL_X = "virt-quad-fifos/i2c-mpu-accel-x" -I2C_MPU_ACCEL_Y = "virt-quad-fifos/i2c-mpu-accel-y" -I2C_MPU_ACCEL_Z = "virt-quad-fifos/i2c-mpu-accel-z" - UART_RX = "virt-quad-fifos/uart-rx" UART_TX = "virt-quad-fifos/uart-tx" require 'test/unit/assertions' require 'timeout' require 'thread' +require 'scanf' include Test::Unit::Assertions # Utility functions @@ -80,14 +67,32 @@ def get_motor_averages(times, total_time) motor_sums.map {|val| val / times} end -def delay_spin_cursor(delay) - fps = 10 - chars = %w[| / - \\] - iteations = delay * fps - iter = 0 - iteations.times() do - print chars[(iter+=1) % chars.length] - sleep (1.0/fps) - print "\b" +def send_packet(bytes) + File.write(UART_RX, bytes.pack("C" * bytes.length)) +end + +def recv_packet + fifo = nil + Timeout::timeout(5) { + fifo = File.open(UART_TX) + } + + # Receive the header + msg = [] + for i in 1..7 + c = fifo.read(1) + msg.push(c) + end + + # Receive the remaining data, according to the header specified length + length = msg[5..7].join().unpack("S")[0] + + msg = [] + for i in 1..length + c = fifo.read(1) + msg.push(c) end + fifo.close + + msg.join() end diff --git a/quad/src/computation_graph/test/test_computation_graph.c b/quad/src/computation_graph/test/test_computation_graph.c index e0882d4d1f2a2c89ede879e1f4f2f4c656e45fca..f44d713813d72502f7a8403c67ad8bfe6717a850 100644 --- a/quad/src/computation_graph/test/test_computation_graph.c +++ b/quad/src/computation_graph/test/test_computation_graph.c @@ -13,7 +13,7 @@ static int nequal(double val1, double val2) { return -1; } -int graph_test_one_add() { +int test_adding_2_numbers() { struct computation_graph *graph = create_graph(); int block = graph_add_defined_block(graph, BLOCK_ADD, "Add"); int cblock3 = graph_add_defined_block(graph, BLOCK_CONSTANT, "3"); @@ -29,7 +29,7 @@ int graph_test_one_add() { } -int graph_test_circular_runs() { +int test_computing_cycles() { struct computation_graph *graph = create_graph(); int gain1 = graph_add_defined_block(graph, BLOCK_GAIN, "gain1"); int gain2 = graph_add_defined_block(graph, BLOCK_GAIN, "gain2"); @@ -41,7 +41,7 @@ int graph_test_circular_runs() { return 0; } -int graph_test_circular_resets() { +int test_resetting_cycles() { struct computation_graph *graph = create_graph(); int acum1 = graph_add_defined_block(graph, BLOCK_ACCUMULATE, "accumulator1"); int acum2 = graph_add_defined_block(graph, BLOCK_ACCUMULATE, "accumulator2"); @@ -51,7 +51,7 @@ int graph_test_circular_resets() { } // Tests the accumulator block, thereby testing reset and state changes -int graph_test_accumulator() { +int test_accumulator_state() { struct computation_graph *graph = create_graph(); int cblock = graph_add_defined_block(graph, BLOCK_CONSTANT, "const"); int acum_b = graph_add_defined_block(graph, BLOCK_ACCUMULATE, "accumulator"); @@ -87,7 +87,7 @@ int graph_test_accumulator() { // Tests that a block will only execute once per compute, // even if its output is connected to multiple inputs -int graph_test_single_run() { +int test_that_blocks_only_get_executed_once() { struct computation_graph *graph = create_graph(); int acum_b = graph_add_defined_block(graph, BLOCK_ACCUMULATE, "accumulator"); int add_block = graph_add_defined_block(graph, BLOCK_ADD, "Add"); @@ -106,7 +106,7 @@ int graph_test_single_run() { } // Tests that upon connection of a second child, a block will not reset -int graph_test_reset_rules() { +int tests_that_already_connected_blocks_dont_get_reset() { struct computation_graph *graph = create_graph(); int cblock = graph_add_defined_block(graph, BLOCK_CONSTANT, "5"); graph_set_param_val(graph, cblock, CONST_SET, 5); @@ -132,7 +132,7 @@ int graph_test_reset_rules() { return nequal(result, 5); } -int graph_test_self_loop() { +int test_that_a_self_loop_computation_terminates() { struct computation_graph *graph = create_graph(); int gain1 = graph_add_defined_block(graph, BLOCK_GAIN, "gain1"); graph_set_source(graph, gain1, GAIN_INPUT, gain1, GAIN_RESULT); @@ -141,7 +141,7 @@ int graph_test_self_loop() { return 0; } -int graph_test_update_rules() { +int test_that_nodes_only_update_when_their_inputs_change() { struct computation_graph *graph = create_graph(); int cblock = graph_add_defined_block(graph, BLOCK_CONSTANT, "const"); int acum_b = graph_add_defined_block(graph, BLOCK_ACCUMULATE, "accumulator"); @@ -161,7 +161,7 @@ C1 --->| accum_b1 --->| | Add ---> C2 --->| accum_b2 --->| */ -int graph_test_update_propagation() { +int test_that_updates_propagate_only_to_their_children() { struct computation_graph *graph = create_graph(); int cblock1 = graph_add_defined_block(graph, BLOCK_CONSTANT, "const1"); int cblock2 = graph_add_defined_block(graph, BLOCK_CONSTANT, "const2"); @@ -192,7 +192,7 @@ This caused problems, because if a node had its output to two things, then it wo Since it didn't get marked as "updated" when it got connected to the computation path, and it had its original "updated" flag cleared, the node would never get set. */ -int graph_test_update_disconnected() { +int test_that_nodes_get_executed_when_updated_even_if_disconnected() { printf("\n\n---------\n"); struct computation_graph *graph = create_graph(); int d_block = graph_add_defined_block(graph, BLOCK_CONSTANT, "const1"); @@ -213,7 +213,7 @@ int graph_test_update_disconnected() { return nequal(set_val, 2*1.2345); } -int graph_test_get_source() { +int test_that_the_get_source_call_works_normally() { struct computation_graph *graph = create_graph(); int add_block = graph_add_defined_block(graph, BLOCK_ADD, "Add"); int cblock3 = graph_add_defined_block(graph, BLOCK_CONSTANT, "3"); @@ -228,7 +228,7 @@ int graph_test_get_source() { } } -int graph_test_get_source_null() { +int test_that_the_get_source_call_returns_ID_neg_1_when_invalid_ID_is_passed() { struct computation_graph *graph = create_graph(); int add_block = graph_add_defined_block(graph, BLOCK_ADD, "Add"); @@ -241,7 +241,7 @@ int graph_test_get_source_null() { } } -int graph_test_add_by_id() { +int test_that_new_nodes_can_be_created_by_ID() { struct computation_graph *graph = create_graph(); int desired_id = 87; int add_block = graph_add_node_id(graph, desired_id, "Add", &node_add_type); @@ -264,18 +264,18 @@ int graph_test_add_by_id() { } int main() { - test(graph_test_one_add, "Test adding 2 numbers"); - test(graph_test_circular_runs, "Test computing cycles"); - test(graph_test_circular_resets, "Test resetting cycles"); - test(graph_test_accumulator, "Test accumulator (state)"); - test(graph_test_single_run, "Test that blocks only get executed once"); - test(graph_test_reset_rules, "Tests that already connected blocks don't get reset"); - test(graph_test_self_loop, "Tests that a self-loop computation terminates"); - 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(graph_test_get_source, "Tests that the get_source call works normally"); - test(graph_test_get_source_null, "Tests that the get_source call returns ID -1 when invalid ID is passed"); - test(graph_test_add_by_id, "Tests that new nodes can be created by ID"); - return test_summary(); + TEST(test_adding_2_numbers); + TEST(test_computing_cycles); + TEST(test_resetting_cycles); + TEST(test_accumulator_state); + TEST(test_that_blocks_only_get_executed_once); + TEST(tests_that_already_connected_blocks_dont_get_reset); + TEST(test_that_a_self_loop_computation_terminates); + TEST(test_that_nodes_only_update_when_their_inputs_change); + TEST(test_that_updates_propagate_only_to_their_children); + TEST(test_that_nodes_get_executed_when_updated_even_if_disconnected); + TEST(test_that_the_get_source_call_works_normally); + TEST(test_that_the_get_source_call_returns_ID_neg_1_when_invalid_ID_is_passed); + TEST(test_that_new_nodes_can_be_created_by_ID); + return test_summary(); } diff --git a/quad/src/quad_app/PID.c b/quad/src/quad_app/PID.c deleted file mode 100644 index 185e7b8dc6161616321bd8fae82f5dd709f94174..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/PID.c +++ /dev/null @@ -1,63 +0,0 @@ -/* - * PID.c - * - * Created on: Nov 10, 2014 - * Author: ucart - */ - -#include "PID.h" -#include <math.h> -#include <float.h> - -// The generic PID diagram. This function takes in pid parameters (PID_t * pid) and calculates the output "pid_correction" -// part based on those parameters. -// -// + --- error ------------------ P + --- ---------------------------- -// setpoint ---> / sum \ --------->| Kp * error |--------------->/ sum \ -------->| output: "pid_correction" | -// \ / | ------------------ \ / ---------------------------- -// --- | --- || -// - ^ | + ^ ^ + || -// | | ------------------------------- | | ------- \/------------ -// | |----->| Ki * accumulated error * dt |----+ | | | -// | | ------------------------------- I | | SYSTEM | -// | | | | | -// | | | --------||------------ -// | | | || -// | | ---------------------------------- | || -// | |----->| Kd * (error - last error) / dt |----+ || -// | ---------------------------------- D || -// | || -// | -----------\/----------- -// |____________________________________________________________| Sensor measurements: | -// | "current point" | -// ------------------------ -// -PID_values pid_computation(PID_t *pid) { - - float P = 0.0, I = 0.0, D = 0.0; - - // calculate the current error - float error = pid->setpoint - pid->current_point; - - // Accumulate the error (if Ki is less than epsilon, rougly 0, - // then reset the accumulated error for safety) - if (fabs(pid->Ki) <= FLT_EPSILON) { - pid->acc_error = 0; - } else { - pid->acc_error += error; - } - - float change_in_error = error - pid->prev_error; - - // Compute each term's contribution - P = pid->Kp * error; - I = pid->Ki * pid->acc_error * pid->dt; - D = pid->Kd * (change_in_error / pid->dt); - - PID_values ret = {P, I, D, error, change_in_error, P + I + D}; - - pid->prev_error = error; // Store the current error into the PID_t - - pid->pid_correction = P + I + D; // Store the computed correction - return ret; -} diff --git a/quad/src/quad_app/README.txt b/quad/src/quad_app/README.txt deleted file mode 100644 index 0e065fbfb65ff25e0844aa10225af4b34d0b07ab..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/README.txt +++ /dev/null @@ -1 +0,0 @@ -This application is the PID implementation of the modular control loop. This is the same implementation as the existing quad controller. The mixer in this application needs to be changed to be correct according to common implementation. diff --git a/quad/src/quad_app/control_algorithm.c b/quad/src/quad_app/control_algorithm.c index 69729052e88c8f509a6bf27450aa01f979fb3351..624c0642abfd47bc4de3cc586d9226dca28fa2a6 100644 --- a/quad/src/quad_app/control_algorithm.c +++ b/quad/src/quad_app/control_algorithm.c @@ -354,8 +354,8 @@ int control_algorithm_init(parameter_t * ps) // also reset the previous error and accumulated error from the position PIDs if((cur_fm_switch == AUTO_FLIGHT_MODE) && (user_defined_struct->engaging_auto == 2)) { - graph_set_param_val(graph, ps->x_set, CONST_SET, 0); - graph_set_param_val(graph, ps->y_set, CONST_SET, 0); + graph_set_param_val(graph, ps->x_set, CONST_SET, sensor_struct->currentQuadPosition.x_pos); + graph_set_param_val(graph, ps->y_set, CONST_SET, sensor_struct->currentQuadPosition.y_pos); graph_set_param_val(graph, ps->alt_set, CONST_SET, sensor_struct->currentQuadPosition.alt_pos); graph_set_param_val(graph, ps->yaw_set, CONST_SET, sensor_struct->currentQuadPosition.yaw); diff --git a/quad/src/quad_app/control_algorithm.h b/quad/src/quad_app/control_algorithm.h index 8e8a15b79b705fe025c57965b45f8f975eadfb1b..92c0feeac5a4121319b8fbf1e28b0b477cb8a3c5 100644 --- a/quad/src/quad_app/control_algorithm.h +++ b/quad/src/quad_app/control_algorithm.h @@ -12,7 +12,6 @@ #include "log_data.h" #include "sensor_processing.h" -#include "quadposition.h" #include "type_def.h" /** diff --git a/quad/src/quad_app/controllers.c b/quad/src/quad_app/controllers.c deleted file mode 100644 index 14abde800f5ea36af1154894c29fdf18e680067f..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/controllers.c +++ /dev/null @@ -1,48 +0,0 @@ -/* - * controllers.c - * - * Created on: Oct 11, 2014 - * Author: ucart - */ - -/** - * Lots of useful information in controllers.h, look in there first - */ -#include "controllers.h" -#include "quadposition.h" -#include "util.h" -#include "stdio.h" -#include <math.h> - -// 0 was -6600 -//int motor0_bias = -4500, motor1_bias = 100, motor2_bias = 5300, motor3_bias = 10300; -int motor0_bias = -9900, motor1_bias = -200, motor2_bias = -10200, motor3_bias = 250; - -/** - * Takes the raw signal inputs from the receiver and filters it so the - * quadcopter doesn't flip or do something extreme - */ -void filter_PWMs(int* mixer) { - -} - -/** - * Converts PWM signals into 4 channel pitch, roll, yaw, throttle - */ -// javey: unused -void PWMS_to_Aero(int* PWMs, int* aero) { - /** - * Reference used to derive equations - */ - // pwm0 = throttle_base - pitch_base + yaw_base; - // pwm1 = throttle_base + roll_base - yaw_base; - // pwm2 = throttle_base - roll_base - yaw_base; - // pwm3 = throttle_base + pitch_base + yaw_base; - - aero[THROTTLE] = (PWMs[0] + PWMs[1] + PWMs[2] + PWMs[3]) / 4; - aero[ROLL] = (PWMs[1] - PWMs[2]) / 2; - aero[PITCH] = (PWMs[3] - PWMs[0]) / 2; - aero[YAW] = (PWMs[3] + PWMs[0] - PWMs[1] - PWMs[2]) / 4; -} - - diff --git a/quad/src/quad_app/controllers.h b/quad/src/quad_app/controllers.h index 40c7832601fd0509a002cb2f5c3c29fa80c304ff..2b6f38cc5fc3c87db0eddea0c199868049484df9 100644 --- a/quad/src/quad_app/controllers.h +++ b/quad/src/quad_app/controllers.h @@ -8,7 +8,6 @@ #define _CONTROLLERS_H #include "util.h" -#include "quadposition.h" /** * diff --git a/quad/src/quad_app/gam.h b/quad/src/quad_app/gam.h deleted file mode 100644 index 0f4803e8d2a2cb50e6733acb278529ebb658f636..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/gam.h +++ /dev/null @@ -1,38 +0,0 @@ -#ifndef _GAM_H -#define _GAM_H - -//Gyro, accelerometer, and magnetometer data structure -//Used for reading an instance of the sensor data -typedef struct { - - // GYRO - //Xint16 raw_gyro_x, raw_gyro_y, raw_gyro_z; - - float gyro_xVel_p; // In degrees per second - float gyro_yVel_q; - float gyro_zVel_r; - - // ACCELEROMETER - //Xint16 raw_accel_x, raw_accel_y, raw_accel_z; - - float accel_x; //In g - float accel_y; - float accel_z; - - float accel_roll; - float accel_pitch; - - - // MAG - //Xint16 raw_mag_x, raw_mag_y, raw_mag_z; - - float heading; // In degrees - - float mag_x; //Magnetic north: ~50 uT - float mag_y; - float mag_z; - - - -}gam_t; -#endif /* _GAM_H */ diff --git a/quad/src/quad_app/hw_iface.h b/quad/src/quad_app/hw_iface.h index 66eac0541045409ba37cbb28cd5c52474d80be67..03aa86e66da8e7f6f2f152b33602cc99280346f9 100644 --- a/quad/src/quad_app/hw_iface.h +++ b/quad/src/quad_app/hw_iface.h @@ -1,8 +1,6 @@ #ifndef HW_IFACE_H #define HW_IFACE_H -#include "xbasic_types.h" - /** * Hardware Interfaces * @@ -15,6 +13,11 @@ * hardware layer appropriate for your circumstance: * ../../xsdk_worksapce/real_quad -> running quad_app on the Zybo * ../virt_quad -> running quad_app in a Unix environment + * + * Function Pointer Return Values: + * - All driver functions return the error code + * - 0 for success + * - nonzero otherwise */ // Forward declared types diff --git a/quad/src/quad_app/new_PID.h b/quad/src/quad_app/new_PID.h deleted file mode 100644 index fae2778ec8b422875e1d88d6ae98a70dee00a8e3..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/new_PID.h +++ /dev/null @@ -1,57 +0,0 @@ -/* - * PID.h - * - * Created on: Nov 10, 2014 - * Author: ucart - */ - -#ifndef PID_H_ -#define PID_H_ - -#include "type_def.h" - -// Yaw constants - -// when using units of radians -#define YAW_ANGULAR_VELOCITY_KP 200.0 * 2292.0f -#define YAW_ANGULAR_VELOCITY_KI 0.0f -#define YAW_ANGULAR_VELOCITY_KD 0.0f -#define YAW_ANGLE_KP 2.6f -#define YAW_ANGLE_KI 0.0f -#define YAW_ANGLE_KD 0.0f - -// when using units of radians -#define ROLL_ANGULAR_VELOCITY_KP 100.0 * 46.0f -#define ROLL_ANGULAR_VELOCITY_KI 0.0f -#define ROLL_ANGULAR_VELOCITY_KD 100.0 * 5.5f -#define ROLL_ANGLE_KP 15.0f -#define ROLL_ANGLE_KI 0.0f -#define ROLL_ANGLE_KD 0.2f -#define YPOS_KP 0.08f -#define YPOS_KI 0.01f -#define YPOS_KD 0.1f - - -//Pitch constants - -// when using units of radians -#define PITCH_ANGULAR_VELOCITY_KP 100.0 * 46.0f -#define PITCH_ANGULAR_VELOCITY_KI 0.0f -#define PITCH_ANGULAR_VELOCITY_KD 100.0 * 5.5f -#define PITCH_ANGLE_KP 15.0f -#define PITCH_ANGLE_KI 0.0f -#define PITCH_ANGLE_KD 0.2f -#define XPOS_KP 0.08f -#define XPOS_KI 0.01f -#define XPOS_KD 0.1f - - -//Throttle constants -#define ALT_ZPOS_KP -9804.0f -#define ALT_ZPOS_KI -817.0f -#define ALT_ZPOS_KD -7353.0f - -// Computes control error and correction -PID_values pid_computation(PID_t *pid); - -#endif /* PID_H_ */ diff --git a/quad/src/quad_app/new_log_data.c b/quad/src/quad_app/new_log_data.c deleted file mode 100644 index 7b2b758f2722673336296c4a3d3f7525b8d4de91..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/new_log_data.c +++ /dev/null @@ -1,225 +0,0 @@ -/* - * log_data.c - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -/* - #include "log_data.h" - -// Current index of the log array -int arrayIndex = 0; -// Size of the array -int arraySize = LOG_STARTING_SIZE; -int resized = 0; - -// The number of times we resized the array -int resizeCount = 0; - -// Pointer to point to the array with all the logging information -// for now its not dynamic -log_t logArray[LOG_STARTING_SIZE * 3];// up to 60 seconds of log - -int log_data(log_t* log_struct) -{ - updateLog(*log_struct); - return 0; -} - -* - * Fills up an xbox hueg amount of memory with log data - -void updateLog(log_t log_struct){ - // If the first iteration, allocate enough memory for "arraySize" elements of logging -// if(logArray == NULL){ -// // size in memory is 1,720,320 bytes (1.64 megabytes) because logging struct is 420 bytes each -// // up to 20 seconds of log before resizing -// logArray = malloc(LOG_STARTING_SIZE * sizeof(log_t)); -// uart0_sendStr("initialized log array.\n"); -// sleep(1); -// } - - // semi dynamic log -// if((arrayIndex >= arraySize - 1) && (!resized)){ -// realloc(logArray, LOG_STARTING_SIZE * 3 * sizeof(log_t)); // up to 60 seconds of log -// resized = 1; -// arraySize = LOG_STARTING_SIZE * 3; -// uart0_sendStr("resized log array.\n"); -// sleep(1); -// } - - if(arrayIndex >= arraySize - 1) - { - return; - } - - // Add log to the array - logArray[arrayIndex++] = log_struct; - - // If the index is too big, reallocate memory to double the size as before -// if(arrayIndex == arraySize){ -// arraySize *= 2; -// logArray = (log_t *) realloc(logArray, arraySize * sizeof(log_t)); -// ++resizeCount; -// } -// else if(arrayIndex > arraySize){ -// // Something fishy has occured -// xil_printf("Array index is out of bounds. This shouldn't happen but somehow you did the impossible\n\r"); -// } -} - - -* - * Prints all the log information. - * - * TODO: This should probably be transmitting in binary instead of ascii - - -void printLogging(){ - int i, numBytes; - char buf[2304] = {}; - char comments[256] = {}; - char header[1024] = {}; - char units [1024] = {}; - - char tempLog[4096*2] = {}; - - sprintf(comments, "# MicroCART On-board Quad Log\r\n# Sample size: %d\r\n", arrayIndex); - sprintf(header, "%%Time\t" "LoopPeriod\t" - - //current points (measurements) - "X_Current_Position\t" "Y_Current_Position\t" "Z_Current_Position\t" - "Cam_Meas_Roll\tCam_Meas_Pitch\tCam_Meas_Yaw\t" - "Quad_Meas_Roll\tQuad_Meas_Pitch\t" - "roll_velocity\tpitch_velocity\tyaw_velocity\t" - - //setpoints - "X_setpoint\t" "Y_setpoint\t" "Z_setpoint\t" - "Roll_setpoint\tPitch_setpoint\tYaw_setpoint\t" - "Roll_vel_setpoint\tPitch_vel_setpoint\tYaw_vel_setpoint\t" - - //corrections - "PID_x\t" - "PID_y\t" - "PID_z\t" - "PID_roll\t" - "PID_pitch\t" - "PID_yaw\t" - "PID_roll_vel\t" - "PID_pitch_vel\t" - "PID_yaw_vel\t" - - //trims - "Roll_trim\tPitch_trim\tYaw_trim\tThrottle_trim\t" - - //motor commands - "Motor_0\tMotor_1\tMotor_2\tMotor_3\n" - - ); - - - sprintf(units, "&sec\tsec\t" - - //current points - "meters\tmeters\tmeters\t" - "radians\tradians\tradians\t" - "radians\tradians\t" - "radians//sec\tradians//sec\tradians//sec\t" - - //setpoints - "meters\tmeters\tmeters\t" - "radians\tradians\tradians\t" - "radians//sec\tradians//sec\tradians//sec\t" - - //corrections - "radians\tradians\tradians\t" - "radians//sec\tradians//sec\tradians//sec\t" - "none\tnone\tnone\t" - - //trims - "none\tnone\tnone\tnone\t" - - //motors - "none\tnone\tnone\tnone\n" - - ); - - strcat(buf,comments); - strcat(buf,header); - strcat(buf,units); - - - numBytes = logData(buf, tempLog); - uart0_sendBytes(tempLog, strlen(tempLog)); - usleep(100000); - - *********************** - print & send log data - for(i = 0; i < arrayIndex; i++){ - char* logLine = format(logArray[i]); - numBytes = logData(logLine, tempLog); - uart0_sendBytes(tempLog, numBytes); - usleep(10000); - //free(logLine); - //break; - } -} - - -char* format(log_t log){ - char *retString = malloc(4096*2); - - sprintf(retString, "%.3f\t%.4f\t" //Time and TimeSlice - - // current points - "%.3f\t%.3f\t%.3f\t" - "%.3f\t%.3f\t%.3f\t" - "%.3f\t%.3f\t" - "%.3f\t%.3f\t%.3f\t" - - //setpoints - "%.3f\t%.3f\t%.3f\t" - "%.3f\t%.3f\t%.3f\t" - "%.3f\t%.3f\t%.3f\t" - - //corrections - "%.3f\t%.3f\t%.3f\t" - "%.3f\t%.3f\t%.3f\t" - "%.3f\t%.3f\t%.3f\t" - - //trims - "%d\t%d\t%d\t%d\t" - - //motors - "%d\t%d\t%d\t%d\n" - - ,log.time_stamp, log.time_slice, - - // current points - log.local_x_PID.current_point,log.local_y_PID.current_point, log.altitude_PID.current_point, - log.currentQuadPosition.roll, log.currentQuadPosition.pitch, log.currentQuadPosition.yaw, - log.roll_angle_filtered, log.pitch_angle_filtered, - log.phi_dot, log.theta_dot, log.psi_dot, - - //setpoints - log.local_x_PID.setpoint, log.local_y_PID.setpoint, log.altitude_PID.setpoint, - log.angle_roll_PID.setpoint, log.angle_pitch_PID.setpoint, log.angle_yaw_PID.setpoint, - log.ang_vel_roll_PID.setpoint, log.ang_vel_pitch_PID.setpoint, log.ang_vel_pitch_PID.setpoint, - - //corrections - log.local_x_PID_values.pid_correction, log.local_y_PID_values.pid_correction, log.altitude_PID_values.pid_correction, - log.angle_roll_PID_values.pid_correction, log.angle_pitch_PID_values.pid_correction, log.angle_yaw_PID_values.pid_correction, - log.ang_vel_roll_PID_values.pid_correction, log.ang_vel_pitch_PID_values.pid_correction, log.ang_vel_yaw_PID_values.pid_correction, - - //trims - log.trims.roll, log.trims.pitch, log.trims.yaw, log.trims.throttle, - - //motors - log.motors[0], log.motors[1], log.motors[2], log.motors[3] - ); - - - return retString; -} -*/ diff --git a/quad/src/quad_app/new_log_data.h b/quad/src/quad_app/new_log_data.h deleted file mode 100644 index 13e713a9ecd1ea71fd799de4860d36808bc2f856..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/new_log_data.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * log_data.h - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -#ifndef LOG_DATA_H_ -#define LOG_DATA_H_ - -#include <stdio.h> -#include <stdlib.h> -#include <string.h> -#include "PID.h" -#include "type_def.h" -#include "sleep.h" -#include "communication.h" - -#define LOG_STARTING_SIZE 4096 //262144 // 2^18 32768 2^15 - - -/** - * @brief - * Logs the data obtained throughout the controller loop. - * - * @param log_struct - * structure of the data to be logged - * - * @return - * error message - * - */ - int log_data(log_t* log_struct); - - /** - * Fills up an xbox hueg amount of memory with log data - */ - void updateLog(log_t log_struct); - - /** - * Prints all the log information. - */ - void printLogging(); - - char* format(log_t log); - -#endif /* LOG_DATA_H_ */ diff --git a/quad/src/quad_app/old_log_data.h b/quad/src/quad_app/old_log_data.h deleted file mode 100644 index 13e713a9ecd1ea71fd799de4860d36808bc2f856..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/old_log_data.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * log_data.h - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -#ifndef LOG_DATA_H_ -#define LOG_DATA_H_ - -#include <stdio.h> -#include <stdlib.h> -#include <string.h> -#include "PID.h" -#include "type_def.h" -#include "sleep.h" -#include "communication.h" - -#define LOG_STARTING_SIZE 4096 //262144 // 2^18 32768 2^15 - - -/** - * @brief - * Logs the data obtained throughout the controller loop. - * - * @param log_struct - * structure of the data to be logged - * - * @return - * error message - * - */ - int log_data(log_t* log_struct); - - /** - * Fills up an xbox hueg amount of memory with log data - */ - void updateLog(log_t log_struct); - - /** - * Prints all the log information. - */ - void printLogging(); - - char* format(log_t log); - -#endif /* LOG_DATA_H_ */ diff --git a/quad/src/quad_app/packet_processing.c b/quad/src/quad_app/packet_processing.c deleted file mode 100644 index 8652c92335a2c778569e6e9e5a98591e155ba626..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/packet_processing.c +++ /dev/null @@ -1,46 +0,0 @@ -/* - * process_packet.c - * - * Created on: Mar 2, 2016 - * Author: ucart - */ -#include "packet_processing.h" -#include "type_def.h" -#include "util.h" -#include "communication.h" - -#define DEBUG 0 - -tokenList_t tokenize(char* cmd) { - int maxTokens = 16; - tokenList_t ret; - ret.numTokens = 0; - ret.tokens = malloc(sizeof(char *)* 20 * maxTokens); - - int i = 0; - ret.tokens[0] = NULL; - char* token = strtok(cmd, " "); - while (token != NULL && i < maxTokens - 1) { - ret.tokens[i] = malloc(strlen(token) + 10); - strcpy(ret.tokens[i], token); - ret.tokens[++i] = NULL; - ret.numTokens++; - token = strtok(NULL, " "); - } - - return ret; -} - -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; -} diff --git a/quad/src/quad_app/packet_processing.h b/quad/src/quad_app/packet_processing.h deleted file mode 100644 index 55a5494b3e1535ac46db7abdaa0ee18b2591f212..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/packet_processing.h +++ /dev/null @@ -1,23 +0,0 @@ -/* - * process_packet.h - * - * Created on: Mar 2, 2016 - * Author: ucart - */ - -#ifndef PROCESS_PACKET_H_ -#define PROCESS_PACKET_H_ - -#include <stdlib.h> -#include <string.h> -#include <stdio.h> -#include "type_def.h" - -tokenList_t tokenize(char* cmd); -int processUpdate(unsigned char* update, quadPosition_t* currentQuadPosition); -//int processCommand(stringBuilder_t * sb, setpoint_t * setpoint_struct, parameter_t * parameter_struct); -int doProcessing(char* cmd, tokenList_t * tokens, setpoint_t * setpoint_struct, parameter_t * parameter_struct); -float getFloat(unsigned char* str, int pos); -int getInt(unsigned char* str, int pos); - -#endif /* PROCESS_PACKET_H_ */ diff --git a/quad/src/quad_app/quad_app.c b/quad/src/quad_app/quad_app.c index 42b32b75caca729cc694884e502aa2f0f7f5f527..561df5b1a26cb6394d487751cab9aeef5c227b7a 100644 --- a/quad/src/quad_app/quad_app.c +++ b/quad/src/quad_app/quad_app.c @@ -13,7 +13,6 @@ #include "sensor_processing.h" #include "control_algorithm.h" #include "send_actuator_commands.h" -#include "update_gui.h" #include "communication.h" #include "mio7_led.h" @@ -71,8 +70,6 @@ int quad_main(int (*setup_hardware)(hardware_t *hardware_struct)) else { kill_motors(&(structs.hardware_struct.motors)); } - // update the GUI - update_GUI(&(structs.log_struct)); if (!this_kill_condition) { // Log the data collected in this loop diff --git a/quad/src/quad_app/quadposition.h b/quad/src/quad_app/quadposition.h deleted file mode 100644 index 05011e04e6289f951700e838b666634b04b4cbc9..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/quadposition.h +++ /dev/null @@ -1,6 +0,0 @@ -#ifndef _QUADPOSITION_H -#define _QUADPOSITION_H - - - -#endif /* _QUADPOSITION_H */ diff --git a/quad/src/quad_app/sensor.c b/quad/src/quad_app/sensor.c index 6fcf5277a2fdbc81d5e8fa8eda1b2ee0b0c1fdb4..6ae875ce931c2ac931de5c18f427acdf85d0fa1a 100644 --- a/quad/src/quad_app/sensor.c +++ b/quad/src/quad_app/sensor.c @@ -22,9 +22,9 @@ int sensor_init(hardware_t *hardware_struct, raw_sensor_t * raw_sensor_struct, s if (imu->reset(imu, &raw_sensor_struct->gam)) { return -1; } - //if (lidar->reset(lidar, &raw_sensor_struct->lidar)) { - // return -1; - //} + if (lidar->reset(lidar, &raw_sensor_struct->lidar)) { + return -1; + } if (of->reset(of, &raw_sensor_struct->optical_flow)) { return -1; } @@ -49,11 +49,11 @@ int get_sensors(hardware_t *hardware_struct, log_t* log_struct, user_input_t* us status = imu->read(imu, &raw_sensor_struct->gam); updateError(&(raw_sensor_struct->gam.error), status); - //status = lidar->read(lidar, &lidar_val); - //updateError(&(raw_sensor_struct->lidar.error), status); - //if (status == 0) { - // raw_sensor_struct->lidar_distance_m = lidar_val.distance_m; - //} + status = lidar->read(lidar, &lidar_val); + updateError(&(raw_sensor_struct->lidar.error), status); + if (status == 0) { + raw_sensor_struct->lidar_distance_m = lidar_val.distance_m; + } status = of->read(of, &raw_sensor_struct->optical_flow); updateError(&(raw_sensor_struct->optical_flow.error), status); diff --git a/quad/src/quad_app/sensor.h b/quad/src/quad_app/sensor.h index d8b9c2620408626afe187c000564968c006ac867..da359e3e05e94133cc33bdae196f894554021570 100644 --- a/quad/src/quad_app/sensor.h +++ b/quad/src/quad_app/sensor.h @@ -12,7 +12,6 @@ #include "log_data.h" #include "user_input.h" -#include "packet_processing.h" #include "hw_iface.h" /** diff --git a/quad/src/quad_app/sensor_processing.c b/quad/src/quad_app/sensor_processing.c index 43dd611461f69efa4a3c182b349b935a8e24b4cd..80e2c22d38f100d47ae5fe2560ede1602da18305 100644 --- a/quad/src/quad_app/sensor_processing.c +++ b/quad/src/quad_app/sensor_processing.c @@ -9,7 +9,6 @@ #include "log_data.h" #include "sensor.h" #include "conversion.h" -#include "quadposition.h" #include "sensor_processing.h" #include "timer.h" #include <math.h> @@ -35,6 +34,17 @@ int sensor_processing_init(sensor_t* sensor_struct) { return 0; } +/* + * Populates the xVel and yVel fields of flow_data, + * using the flowX and flowY, and the given distance + */ +// Focal length in mm = 16 +static float focal_length_px = 16.0 / (4.0f * 6.0f) * 1000.0f; //original focal lenght: 12mm pixelsize: 6um, binning 4 enabled +void flow_to_vel(px4flow_t* flow_data, double distance) { + flow_data->xVel = distance * -flow_data->flowX / focal_length_px / get_last_loop_time(); + flow_data->yVel = distance * -flow_data->flowY / focal_length_px / get_last_loop_time(); +} + int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_sensor_t* raw_sensor_struct, sensor_t* sensor_struct) { // Filter accelerometer values @@ -102,17 +112,35 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se sensor_struct->roll_angle_filtered = ALPHA * (sensor_struct->roll_angle_filtered + sensor_struct->phi_dot* get_last_loop_time()) + (1. - ALPHA) * accel_roll; - // Z-axis points upward, so negate distance - sensor_struct->lidar_altitude = -raw_sensor_struct->lidar_distance_m; + //sensor_struct->lidar_altitude = -raw_sensor_struct->lidar_distance_m; // Simply copy optical flow data sensor_struct->optical_flow = raw_sensor_struct->optical_flow; //sensor_struct->optical_flow.xVel = biquad_execute(&sensor_struct->flow_x_filt, -sensor_struct->optical_flow.xVel); //sensor_struct->optical_flow.yVel = biquad_execute(&sensor_struct->flow_y_filt, -sensor_struct->optical_flow.yVel); - sensor_struct->optical_flow.xVel = -sensor_struct->optical_flow.xVel; - sensor_struct->optical_flow.yVel = -sensor_struct->optical_flow.yVel; + flow_to_vel(&sensor_struct->optical_flow, raw_sensor_struct->lidar_distance_m); + + /* + * Altitude double complementary filter + */ + static float alt_alpha = 0.9975; + static float filtered_vel = 0; + static float filtered_alt = 0; + static float last_lidar = 0; + + float this_lidar = raw_sensor_struct->lidar_distance_m; + // Acceleration in m/s without gravity + float quad_z_accel = -9.8 * (accel_z + 1); + filtered_vel = alt_alpha*(filtered_vel + quad_z_accel*get_last_loop_time()) + + (1 - alt_alpha)*(this_lidar - last_lidar); + filtered_alt = alt_alpha*(filtered_alt + filtered_vel*get_last_loop_time()) + + (1 - alt_alpha)*(this_lidar); + + last_lidar = this_lidar; + sensor_struct->lidar_altitude = filtered_alt; + return 0; } diff --git a/quad/src/quad_app/update_gui.c b/quad/src/quad_app/update_gui.c deleted file mode 100644 index 320936e5aa73f0309209ab945f56807f72d69d1d..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/update_gui.c +++ /dev/null @@ -1,14 +0,0 @@ -/* - * update_gui.c - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -#include "update_gui.h" - -int update_GUI(log_t* log_struct) -{ - return 0; -} - diff --git a/quad/src/quad_app/update_gui.h b/quad/src/quad_app/update_gui.h deleted file mode 100644 index a348ade955798e225c96f1b59b27d79a75861d59..0000000000000000000000000000000000000000 --- a/quad/src/quad_app/update_gui.h +++ /dev/null @@ -1,28 +0,0 @@ -/* - * update_gui.h - * - * Created on: Feb 20, 2016 - * Author: ucart - */ - -#ifndef UPDATE_GUI_H_ -#define UPDATE_GUI_H_ - -#include <stdio.h> - -#include "log_data.h" - -/** - * @brief - * Updates the user interface. - * - * @param log_struct - * structure of the data to be logged - * - * @return - * error message - * - */ -int update_GUI(log_t* log_struct); - -#endif /* UPDATE_GUI_H_ */ diff --git a/quad/src/queue/test/test_queue.c b/quad/src/queue/test/test_queue.c index 02328d1f90994daa884c28cea06db4c63cca0d9a..aa23c9efa115704f7493042bf078c8be012c35f7 100644 --- a/quad/src/queue/test/test_queue.c +++ b/quad/src/queue/test/test_queue.c @@ -160,11 +160,11 @@ int test_empty() { 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"); + TEST(test_free); + TEST(test_add); + TEST(test_remove); + TEST(test_size); + TEST(test_full); + TEST(test_empty); return test_summary(); } diff --git a/quad/src/test/README.md b/quad/src/test/README.md index 8bec810e243574750c9c5aec2a80434f5c5118fc..229cb6bdf47226078160c4c1616137b167d368ab 100644 --- a/quad/src/test/README.md +++ b/quad/src/test/README.md @@ -1,6 +1,9 @@ Basic Testing Suite in C ---- -This test suite helps you run tests. It handles the result of every test +THIS IS NOT A DIRECTORY OF TESTS. Rather, it is a library of test utility +functions that you can use to write unit tests. + +The functions in this library help handles the result of every test whether it be a success, failure, or segfault, and keeps running until all tests have been executed. It then gives a summary of the test results. @@ -12,11 +15,16 @@ function along with a name you want included in the test report. ```c int main() { - test(test_func, "this test will pass!"); - test(another_func, "this one might fail..."); + TEST(test_func); + TEST(another_func); ... ``` +When writing your `test_func`, you can use the `test_assert` method to perform +basic assertions. If any assertion fails, then `test_func` will fail right +away. If you have multiple assertions in a single `test_func`, the output will +tell you specifically which assertion failed. + Then at the end of your main function, call the `test_summary()` function, and return its return value from your main function. @@ -27,4 +35,8 @@ int main() { } ``` -An `example.c` file is included for reference. \ No newline at end of file +An example of creating a `test/` directory is done in this folder. To run make +the unit tests in your library, run +``` +make test +``` \ No newline at end of file diff --git a/quad/src/test/example/example.c b/quad/src/test/example/example.c deleted file mode 100644 index b757c6e5d5ff9ab0839ebe77b9991c65a2f431ca..0000000000000000000000000000000000000000 --- a/quad/src/test/example/example.c +++ /dev/null @@ -1,24 +0,0 @@ -#include <stdio.h> -#include "test.h" - -int test1() { - puts("hi world."); - return 0; -} - -int test2() { - return 1; -} - -int test3() { - int *bad = NULL; - int x = *bad; - return 0; -} - -int main() { - test(test1, "print hello world"); - test(test2, "just fail"); - test(test3, "survive segfault"); - return test_summary(); -} diff --git a/quad/src/test/test/example.c b/quad/src/test/test/example.c new file mode 100644 index 0000000000000000000000000000000000000000..bca8528ca746f176be9fd6da77992bd51fae7883 --- /dev/null +++ b/quad/src/test/test/example.c @@ -0,0 +1,32 @@ +#include <stdio.h> +#include "test.h" + +int test_always_passes() { + puts("hi world."); + return 0; +} + +int test_always_fails() { + return 1; +} + +int test_assertions() { + test_assert(1 == 1); + test_assert(2 == 3); + test_assert(3 == 3); + return 1; +} + +int test_always_segfaults() { + int *bad = NULL; + int x = *bad; + return 0; +} + +int main() { + TEST(test_always_passes); + TEST(test_always_fails); + TEST(test_assertions); + TEST(test_always_segfaults); + return test_summary(); +} diff --git a/quad/src/virt_quad/README.md b/quad/src/virt_quad/README.md index 3607ec44cadba0f318a6797a296b35a8f687c091..3b263e52847000867fb67a6cb12da244efeca7ee 100644 --- a/quad/src/virt_quad/README.md +++ b/quad/src/virt_quad/README.md @@ -8,17 +8,18 @@ plethoria of things required for flight in Coover 3050. In fact, you don't even have to be in Coover 3050... # Using the Virtual Quad -Start it up: +The virt-quad has help output. Get started with: ``` -make run +./virt-quad ``` -And you can do things with it. You'll notice it will make a bunch of FIFOs in -the current directory. Write to / read from these FIFOs as you see fit. +## Using the UART Driver -## Writing to FIFO from shell +The UART interface is implemented with unix FIFOs. You can treat these FIFOs +as regular unix files. Read from uart-tx to hear with the quad is saying. Write +to uart-rx to tell the quad something. ``` -echo "170000" > virt-quad-fifos/pwm-input-gear # Setting the gear to '1' -cat virt-quad-fifos/pwm-output-motor1 # Read the motor 1 pwm signal +echo "hello world" > virt-quad-fifos/uart-rx +cat virt-quad-fifos/uart-tx ``` \ No newline at end of file diff --git a/quad/src/virt_quad/hw_impl_unix.c b/quad/src/virt_quad/hw_impl_unix.c index d3607f17e16deffee36a4cefe64a6b0a55f15943..e1dbcf9e2469368ce7d14fc0b2bd8ed857f790bf 100644 --- a/quad/src/virt_quad/hw_impl_unix.c +++ b/quad/src/virt_quad/hw_impl_unix.c @@ -28,6 +28,7 @@ struct RCReceiverDriver create_unix_rc_receiver() { struct I2CDriver create_unix_i2c() { struct I2CDriver i2c; i2c.state = NULL; + i2c.busId = 0; i2c.reset = unix_i2c_reset; i2c.write = unix_i2c_write; i2c.read = unix_i2c_read; diff --git a/quad/src/virt_quad/hw_impl_unix_uart.c b/quad/src/virt_quad/hw_impl_unix_uart.c index e39fbedfc06f93a75a8e682cb44d81be98f790bf..e750b29721faeef14b1dd60ec00c50eae00f3421 100644 --- a/quad/src/virt_quad/hw_impl_unix_uart.c +++ b/quad/src/virt_quad/hw_impl_unix_uart.c @@ -30,8 +30,8 @@ int unix_uart_write(struct UARTDriver *self, unsigned char c) { if (fifo >= 0) { printf("%s: %x\n", "uart-tx", c); write(fifo, &c, 1); + close(fifo); } - close(fifo); return 0; } diff --git a/quad/src/virt_quad/main.c b/quad/src/virt_quad/main.c index 105a8a5e68ae04d21e8001b9eb8c0b78a8629038..9b0c676afb405b3adee7b1adeb6eefc549c66644 100644 --- a/quad/src/virt_quad/main.c +++ b/quad/src/virt_quad/main.c @@ -4,21 +4,35 @@ #include "quad_app.h" #include <fcntl.h> +struct VirtQuadIO *virt_quad_io; +int virt_quad_io_file_descriptor; + +enum CLISubCommand { + START, + GET, + SET, + USAGE, + HELP, +}; + +int start_virt_quad(char *argv[]); int handle_io_output(const char *name); int handle_io_input(const char *name, const char *value_str); void set_shm(float value, float *dest, pthread_mutex_t *lock); void print_shm_float(float *value, pthread_mutex_t *lock); void print_shm_int(int *value, pthread_mutex_t *lock); void usage(char *executable_name); - -struct VirtQuadIO *virt_quad_io; -int virt_quad_io_file_descriptor; +enum CLISubCommand parse_sub_command(char *argv[]); +void open_new_shm_io(); +void open_existing_shm_io(); +void help_sub_command(char *argv[]); /** * Implement each of the hardware interfaces. */ int setup_hardware(hardware_t *hardware) { - hardware->i2c = create_unix_i2c(); + hardware->i2c_0 = create_unix_i2c(); + hardware->i2c_1 = create_unix_i2c(); hardware->rc_receiver = create_unix_rc_receiver(); hardware->motors = create_unix_motors(); hardware->uart = create_unix_uart(); @@ -26,68 +40,99 @@ int setup_hardware(hardware_t *hardware) { hardware->axi_timer = create_unix_axi_timer(); hardware->mio7_led = create_unix_mio7_led(); hardware->sys = create_unix_system(); - hardware->imu = create_unix_imu(&hardware->i2c); - hardware->lidar = create_unix_lidar(&hardware->i2c); - hardware->of = create_unix_optical_flow(&hardware->i2c); + hardware->imu = create_unix_imu(&hardware->i2c_0); + hardware->lidar = create_unix_lidar(&hardware->i2c_1); + hardware->of = create_unix_optical_flow(&hardware->i2c_0); return 0; } int main(int argc, char *argv[]) { - int fd; + enum CLISubCommand sub_command = parse_sub_command(argv + 1); + + switch (sub_command) { + case START: + open_new_shm_io(); + start_virt_quad(argv + 2); // will block + break; + case SET: + open_existing_shm_io(); + handle_io_input(argv[2], argv[3]); + break; + case GET: + open_existing_shm_io(); + handle_io_output(argv[2]); + break; + case HELP: + help_sub_command(argv); + break; + case USAGE: + usage(argv[0]); + break; + } - // Decide if we are launching the quad or parsing arguments - if (argv[1] == NULL || strcmp(argv[1], "-q") == 0) { - // launch the quad - - // Allow making the quad quiet - if (argv[1] != NULL && strcmp(argv[1], "-q") == 0) { - fd = open("/dev/null", O_WRONLY); - close(STDOUT_FILENO); - dup2(STDOUT_FILENO, fd); - } - - // Prepare the shared memory for io. Clear memory and initialize. - int *fd = &virt_quad_io_file_descriptor; - *fd = shm_open(VIRT_QUAD_SHARED_MEMORY, O_CREAT | O_RDWR | O_TRUNC, 0666); - ftruncate(*fd, sizeof(struct VirtQuadIO)); - virt_quad_io = mmap(NULL, sizeof(struct VirtQuadIO), PROT_READ | PROT_WRITE, MAP_SHARED, *fd, 0); - pthread_mutexattr_t attr; - pthread_mutexattr_init(&attr); - pthread_mutexattr_setpshared(&attr, PTHREAD_PROCESS_SHARED); - pthread_mutex_init(&virt_quad_io->led_lock, &attr); - pthread_mutex_init(&virt_quad_io->motors_lock, &attr); - pthread_mutex_init(&virt_quad_io->rc_lock, &attr); + return 0; +} + +enum CLISubCommand parse_sub_command(char *argv[]) { + if (argv[0] == NULL) { + return USAGE; + } + else if (strcmp(argv[0], "start") == 0) { + return START; + } + else if (strcmp(argv[0], "help") == 0) { + return HELP; + } + else if (strcmp(argv[0], "get") == 0 && argv[1] != NULL) { + return GET; + } + else if (strcmp(argv[0], "set") == 0 && argv[1] != NULL && argv[2] != NULL) { + return SET; } else { - // parse command line arguments + return USAGE; + } +} - // Open exising shared memory for io. DO NOT CLEAR. - int *fd = &virt_quad_io_file_descriptor; - *fd = shm_open(VIRT_QUAD_SHARED_MEMORY, O_CREAT | O_RDWR, 0666); - virt_quad_io = mmap(NULL, sizeof(struct VirtQuadIO), PROT_READ | PROT_WRITE, MAP_SHARED, *fd, 0); +int start_virt_quad(char *argv[]) { + int fd; - if (strcmp(argv[1], "--help") == 0 || strcmp(argv[1], "-h") == 0) { - usage(argv[0]); - exit(0); - } - else if (strcmp(argv[1], "get") == 0 && argv[2] != NULL) { - handle_io_output(argv[2]); - } - else if (strcmp(argv[1], "set") == 0 && argv[2] != NULL && argv[3] != NULL) { - handle_io_input(argv[2], argv[3]); - } - else { - puts("Error in parsing commands"); - usage(argv[0]); - } - return 0; + // Allow making the quad quiet + if (argv[0] != NULL && strcmp(argv[0], "-q") == 0) { + fd = open("/dev/null", O_WRONLY); + close(STDOUT_FILENO); + dup2(STDOUT_FILENO, fd); } - puts("Starting the quad application"); + puts("Starting the virtual quad."); + puts("Open another tab to query and control the virt quad, using the get and set commands."); quad_main(setup_hardware); return 0; } +void open_new_shm_io() { + // Prepare the shared memory for io. Clear memory and initialize. + int *fd = &virt_quad_io_file_descriptor; + *fd = shm_open(VIRT_QUAD_SHARED_MEMORY, O_CREAT | O_RDWR | O_TRUNC, 0666); + ftruncate(*fd, sizeof(struct VirtQuadIO)); + virt_quad_io = mmap(NULL, sizeof(struct VirtQuadIO), PROT_READ | PROT_WRITE, MAP_SHARED, *fd, 0); + pthread_mutexattr_t attr; + pthread_mutexattr_init(&attr); + pthread_mutexattr_setpshared(&attr, PTHREAD_PROCESS_SHARED); + pthread_mutex_init(&virt_quad_io->led_lock, &attr); + pthread_mutex_init(&virt_quad_io->motors_lock, &attr); + pthread_mutex_init(&virt_quad_io->rc_lock, &attr); + pthread_mutex_init(&virt_quad_io->i2c_lock, &attr); +} + +void open_existing_shm_io() { + // Open exising shared memory for io. DO NOT CLEAR. + int *fd = &virt_quad_io_file_descriptor; + *fd = shm_open(VIRT_QUAD_SHARED_MEMORY, O_CREAT | O_RDWR, 0666); + virt_quad_io = mmap(NULL, sizeof(struct VirtQuadIO), PROT_READ | PROT_WRITE, MAP_SHARED, *fd, 0); +} + + /** * The user wants to read an output by name. Get the output * and print to stdout. @@ -203,25 +248,79 @@ void print_shm_int(int *value, pthread_mutex_t *lock) { } void usage(char *executable_name) { - printf("Usage: %s [ -h | --help | -q ] [ command ]\n", executable_name); + printf("Usage: %s command [ args ]\n", executable_name); puts("Overview:"); puts(" The virtual quad emulates the behavior of the real quad in the Unix"); puts(" environment. Start the virtual quad in one tab (no arguments), and"); puts(" then control the I/O of the quad through commands."); + puts(""); + puts(" For help on a particular command, pass the command name to the help command"); + puts(" Example:"); + printf(" %s help get\n", executable_name); + puts(""); puts("Commands:"); - puts(" get output"); - puts(" set input value"); - puts("Outpus:"); - puts(" led"); - puts(" motors"); - puts("Inputs:"); - puts(" rc_gear"); - puts(" rc_flap"); - puts(" rc_throttle"); - puts(" rc_pitch"); - puts(" rc_roll"); - puts(" rc_yaw"); - puts("Examples:"); - printf(" %s get led # prints 0 or 1 to stdout\n", executable_name); - printf(" in%s set rc_gear 1 # sets gear to \"on\" \n", executable_name); + puts(" help"); + puts(" get"); + puts(" set"); + puts(" start"); + puts(""); +} + +void help_sub_command(char *argv[]) { + if (argv[2] == NULL) { + usage(argv[0]); + } + else if (strcmp(argv[2], "help") == 0) { + puts("Really?"); + } + else if (strcmp(argv[2], "get") == 0) { + printf("Usage: %s get output_name\n", argv[0]); + puts(""); + puts(" Get an output on the virtual quad, specified by its output_name, and print"); + puts(" to stdout"); + puts(""); + puts(" Possible output names"); + puts(" led"); + puts(" motor1"); + puts(" motor2"); + puts(" motor3"); + puts(" motor4"); + puts(""); + } + else if (strcmp(argv[2], "set") == 0) { + printf("Usage: %s set input_name val\n", argv[0]); + puts(""); + puts(" Set the value of an input on the quad, specified by its input_name"); + puts(""); + puts(" Possible input names"); + puts(" rc_throttle"); + puts(" rc_pitch"); + puts(" rc_roll"); + puts(" rc_yaw"); + puts(" rc_gear"); + puts(" rc_flap"); + puts(" i2c_imu_x"); + puts(" i2c_imu_y"); + puts(" i2c_imu_z"); + puts(" i2c_imu_p"); + puts(" i2c_imu_q"); + puts(" i2c_imu_r"); + puts(" i2c_imu_mag_x"); + puts(" i2c_imu_mag_y"); + puts(" i2c_imu_mag_z"); + puts(""); + } + else if (strcmp(argv[2], "start") == 0) { + printf("Usage: %s start [ -q ]\n", argv[0]); + puts(""); + puts(" Start the virtual quad. Exit using ctrl-c. In order to get and set I/O,"); + puts(" you'll need to open another tab."); + puts(""); + puts(" Flags"); + puts(" q - Keep the quad quiet; don't print logs to the stdout"); + puts(""); + } + else { + usage(argv[0]); + } } diff --git a/quad/xsdk_workspace/.gitignore b/quad/xsdk_workspace/.gitignore index 0deb2c3cff4c49e9e7759258b76fa279bc7f381e..ca597b5293028d23740f2c62efb0bb7d138aef1d 100644 --- a/quad/xsdk_workspace/.gitignore +++ b/quad/xsdk_workspace/.gitignore @@ -5,4 +5,7 @@ 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 +zybo_fsbl/Release +zybo_fsbl/Debug +zybo_fsbl/bootimage +TAGS diff --git a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c index 67177ace77753696f8191f2b115d9c56bba9bdbd..da9ed7ffc6346f652d13391ae6acfd738171892b 100644 --- a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c +++ b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c @@ -48,7 +48,7 @@ #define ACCEL_X_BIAS 0.023f #define ACCEL_Y_BIAS 0.009f -#define ACCEL_Z_BIAS 0.087f +#define ACCEL_Z_BIAS 0.0686f int mpu9150_write(struct I2CDriver *i2c, u8 register_addr, u8 data); int mpu9150_read(struct I2CDriver *i2c, u8* recv_buffer, u8 register_addr, int size); diff --git a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_lidar.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_lidar.c index cd49ca3657492b8b1c3b5b491b027fc648dbe404..32d0fad0cd243c3e871c58eaaa10ead16c3d246b 100644 --- a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_lidar.c +++ b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_lidar.c @@ -4,7 +4,7 @@ #include <string.h> #define LIDARLITE_DEVICE_ADDR 0x62 -#define LIDAR_OFFSET 0.02 // Distance from LiDAR sensor to ground, in meters +#define LIDAR_OFFSET (0.016666) // Distance from LiDAR sensor to ground, in meters int lidarlite_write(struct I2CDriver *i2c, u8 register_addr, u8 data); int lidarlite_read(struct I2CDriver *i2c, u8* recv_buffer, u8 register_addr, int size); @@ -37,8 +37,8 @@ int zybo_lidar_read(struct LidarDriver *self, lidar_t *lidar) { // Read the sensor value error = lidarlite_read(i2c, buf, 0x8f, 2); if (error) return error; - float distance_cm = (float)(buf[0] << 8 | buf[1]) - LIDAR_OFFSET; - lidar->distance_m = distance_cm * 0.01; + float distance_cm = (float)(buf[0] << 8 | buf[1]); + lidar->distance_m = (distance_cm * 0.01) + LIDAR_OFFSET; return error; } diff --git a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_optical_flow.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_optical_flow.c index f3ab4d9e66d993b53c6ddc7031bd17dec3450bde..8a7e17d3ac65f3beeb62e253f1ab4067799c342a 100644 --- a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_optical_flow.c +++ b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_optical_flow.c @@ -46,6 +46,9 @@ int zybo_optical_flow_read(struct OpticalFlowDriver *self, px4flow_t *of) { of->xVel = i2cFrame.flowCompX / 1000.; of->yVel = i2cFrame.flowCompY / 1000.; + // They call it "sum", but it's just the latest pixel flow * 10 + of->flowX = (double)i2cFrame.pixelFlowXSum / 10.; + of->flowY = (double)i2cFrame.pixelFlowYSum / 10.; of->quality = i2cFrame.qual; of->distance = i2cFrame.groundDistance / 1000.; } diff --git a/quad/xsdk_workspace/real_quad/src/main.c b/quad/xsdk_workspace/real_quad/src/main.c index d715d8e6538906b99b38f21f50260d801540c4cf..0e874fc05b4ab3ed749856659264f2f6478f286f 100644 --- a/quad/xsdk_workspace/real_quad/src/main.c +++ b/quad/xsdk_workspace/real_quad/src/main.c @@ -53,7 +53,7 @@ int main() //test_zybo_i2c_lidar(); //test_zybo_i2c_all(); //test_zybo_rc_receiver(); - //test_zybo_motors(); + test_zybo_motors(); //test_zybo_uart(); //test_zybo_axi_timer(); test_zybo_uart_comm(); diff --git a/quad/xsdk_workspace/system_bsp/.cproject b/quad/xsdk_workspace/system_bsp/.cproject index 16d2fd27b24cadd9bbd9068ab31f7404474d66d9..58ab3351cc7a84b2307d26a9be45e62c628cc66f 100644 --- a/quad/xsdk_workspace/system_bsp/.cproject +++ b/quad/xsdk_workspace/system_bsp/.cproject @@ -3,8 +3,8 @@ <cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage"> <storageModule moduleId="org.eclipse.cdt.core.settings"> - <cconfiguration id="org.eclipse.cdt.core.default.config.2078347332"> - <storageModule buildSystemId="org.eclipse.cdt.core.defaultConfigDataProvider" id="org.eclipse.cdt.core.default.config.2078347332" moduleId="org.eclipse.cdt.core.settings" name="Configuration"> + <cconfiguration id="org.eclipse.cdt.core.default.config.946402869"> + <storageModule buildSystemId="org.eclipse.cdt.core.defaultConfigDataProvider" id="org.eclipse.cdt.core.default.config.946402869" moduleId="org.eclipse.cdt.core.settings" name="Configuration"> <externalSettings/> <extensions/> </storageModule> diff --git a/quad/xsdk_workspace/system_bsp/system.mss b/quad/xsdk_workspace/system_bsp/system.mss index 901e54a471058d3b3cfbef52689f574ae2ceb2d3..2c47ed63fb85c6b87fabec00cacc13c5ae4fa666 100644 --- a/quad/xsdk_workspace/system_bsp/system.mss +++ b/quad/xsdk_workspace/system_bsp/system.mss @@ -6,8 +6,8 @@ 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 + PARAMETER STDIN = ps7_uart_1 + PARAMETER STDOUT = ps7_uart_1 END diff --git a/quad/xsdk_workspace/zybo_fsbl/.cproject b/quad/xsdk_workspace/zybo_fsbl/.cproject index 8047c604215d0cda99d40a39a7af8fbd78ca1e16..7ddad3fcbf9d707d11bd9f0bb6f2d6a36f1c41c2 100644 --- a/quad/xsdk_workspace/zybo_fsbl/.cproject +++ b/quad/xsdk_workspace/zybo_fsbl/.cproject @@ -3,8 +3,8 @@ <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"> + <cconfiguration id="xilinx.gnu.arm.exe.debug.1528513972"> + <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="xilinx.gnu.arm.exe.debug.1528513972" moduleId="org.eclipse.cdt.core.settings" name="Debug"> <externalSettings/> <extensions> <extension id="com.xilinx.sdk.managedbuilder.XELF.arm" point="org.eclipse.cdt.core.BinaryParser"/> @@ -16,68 +16,68 @@ </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"/> + <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.1528513972" name="Debug" parent="xilinx.gnu.arm.exe.debug"> + <folderInfo id="xilinx.gnu.arm.exe.debug.1528513972." name="/" resourcePath=""> + <toolChain id="xilinx.gnu.arm.exe.debug.toolchain.620865263" 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.1299613950" 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.1331514252" managedBuildOn="true" name="GNU make.Debug" superClass="xilinx.gnu.arm.toolchain.builder.debug"/> + <tool id="xilinx.gnu.arm.c.toolchain.assembler.debug.911778202" name="ARM gcc assembler" superClass="xilinx.gnu.arm.c.toolchain.assembler.debug"> + <inputType id="xilinx.gnu.assembler.input.2001882527" 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"> + <tool id="xilinx.gnu.arm.c.toolchain.compiler.debug.1840889584" 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.2110622919" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.1324950494" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.max" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.1010106927" 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"/> + <inputType id="xilinx.gnu.arm.c.compiler.input.164824730" 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"> + <tool id="xilinx.gnu.arm.cxx.toolchain.compiler.debug.247997005" 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.1779591449" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.1320442366" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.max" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.1122443388" 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"> + <tool id="xilinx.gnu.arm.toolchain.archiver.1400731677" name="ARM archiver" superClass="xilinx.gnu.arm.toolchain.archiver"/> + <tool id="xilinx.gnu.arm.c.toolchain.linker.debug.345997425" name="ARM gcc linker" superClass="xilinx.gnu.arm.c.toolchain.linker.debug"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.1716168836" 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"> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.1873644137" 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"> + <option id="xilinx.gnu.c.linker.option.lscript.1950983133" superClass="xilinx.gnu.c.linker.option.lscript" value="../src/lscript.ld" valueType="string"/> + <option id="xilinx.gnu.c.link.option.libs.598950432" 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"> + <option id="xilinx.gnu.c.link.option.paths.58794466" 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"> + <inputType id="xilinx.gnu.linker.input.103080881" 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"/> + <inputType id="xilinx.gnu.linker.input.lscript.428167088" 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"> + <tool id="xilinx.gnu.arm.cxx.toolchain.linker.debug.566442706" name="ARM g++ linker" superClass="xilinx.gnu.arm.cxx.toolchain.linker.debug"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.1863640969" 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"> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.2096513062" 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"/> + <option id="xilinx.gnu.c.linker.option.lscript.1103422420" 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"/> + <tool id="xilinx.gnu.arm.size.debug.2048630709" 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"> + <cconfiguration id="xilinx.gnu.arm.exe.release.819164381"> + <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="xilinx.gnu.arm.exe.release.819164381" moduleId="org.eclipse.cdt.core.settings" name="Release"> <externalSettings/> <extensions> <extension id="com.xilinx.sdk.managedbuilder.XELF.arm" point="org.eclipse.cdt.core.BinaryParser"/> @@ -89,60 +89,60 @@ </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"/> + <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.819164381" name="Release" parent="xilinx.gnu.arm.exe.release"> + <folderInfo id="xilinx.gnu.arm.exe.release.819164381." name="/" resourcePath=""> + <toolChain id="xilinx.gnu.arm.exe.release.toolchain.1240523721" 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.1592659856" 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.220781107" managedBuildOn="true" name="GNU make.Release" superClass="xilinx.gnu.arm.toolchain.builder.release"/> + <tool id="xilinx.gnu.arm.c.toolchain.assembler.release.1719774153" name="ARM gcc assembler" superClass="xilinx.gnu.arm.c.toolchain.assembler.release"> + <inputType id="xilinx.gnu.assembler.input.431288829" 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"> + <tool id="xilinx.gnu.arm.c.toolchain.compiler.release.2059219877" 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.1308162708" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.1671222344" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.none" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.1131284540" 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"/> + <inputType id="xilinx.gnu.arm.c.compiler.input.1631463841" 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"> + <tool id="xilinx.gnu.arm.cxx.toolchain.compiler.release.891744552" 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.1151102494" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.1077797144" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.none" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.inferred.swplatform.includes.1913917319" 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"> + <tool id="xilinx.gnu.arm.toolchain.archiver.1118360987" name="ARM archiver" superClass="xilinx.gnu.arm.toolchain.archiver"/> + <tool id="xilinx.gnu.arm.c.toolchain.linker.release.1132751753" name="ARM gcc linker" superClass="xilinx.gnu.arm.c.toolchain.linker.release"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.1917836743" 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"> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.383672501" 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"> + <option id="xilinx.gnu.c.linker.option.lscript.1608063800" superClass="xilinx.gnu.c.linker.option.lscript" value="../src/lscript.ld" valueType="string"/> + <option id="xilinx.gnu.c.link.option.libs.1281241736" 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"> + <option id="xilinx.gnu.c.link.option.paths.40091586" 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"> + <inputType id="xilinx.gnu.linker.input.926037696" 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"/> + <inputType id="xilinx.gnu.linker.input.lscript.1292679303" 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"> + <tool id="xilinx.gnu.arm.cxx.toolchain.linker.release.823586348" name="ARM g++ linker" superClass="xilinx.gnu.arm.cxx.toolchain.linker.release"> + <option id="xilinx.gnu.linker.inferred.swplatform.lpath.1966466748" 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"> + <option id="xilinx.gnu.linker.inferred.swplatform.flags.1228570640" 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"/> + <option id="xilinx.gnu.c.linker.option.lscript.1403296691" 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"/> + <tool id="xilinx.gnu.arm.size.release.1130359049" name="ARM Print Size" superClass="xilinx.gnu.arm.size.release"/> </toolChain> </folderInfo> </configuration> @@ -152,20 +152,20 @@ </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"/> + <project id="zybo_fsbl.xilinx.gnu.arm.exe.36875234" 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"> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.debug.1528513972;xilinx.gnu.arm.exe.debug.1528513972.;xilinx.gnu.arm.c.toolchain.compiler.debug.1840889584;xilinx.gnu.arm.c.compiler.input.164824730"> <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"> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.release.819164381;xilinx.gnu.arm.exe.release.819164381.;xilinx.gnu.arm.c.toolchain.compiler.release.2059219877;xilinx.gnu.arm.c.compiler.input.1631463841"> <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."> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.release.819164381;xilinx.gnu.arm.exe.release.819164381."> <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."> + <scannerConfigBuildInfo instanceId="xilinx.gnu.arm.exe.debug.1528513972;xilinx.gnu.arm.exe.debug.1528513972."> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.xilinx.managedbuilder.ui.ARMGCCManagedMakePerProjectProfileC"/> </scannerConfigBuildInfo> </storageModule> diff --git a/quad/xsdk_workspace/zybo_fsbl/.gitignore b/quad/xsdk_workspace/zybo_fsbl/.gitignore deleted file mode 100644 index a92e1611ddfdb7685cb2660245489c5bfdea3494..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/zybo_fsbl/.gitignore +++ /dev/null @@ -1,5 +0,0 @@ -*.o -*.d -*.elf -*.size -bootimage/ \ No newline at end of file diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.c b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.c index 182b94b57bd1df0e3e0ca275aca23631f9375d65..2c7ad97ad33b532925df749643c5395076b72cfa 100644 --- a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.c +++ b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.c @@ -2512,23 +2512,23 @@ unsigned long ps7_mio_init_data_1_0[] = { // .. L2_SEL = 0 // .. ==> 0XF8000730[4:3] = 0x00000000U // .. ==> MASK : 0x00000018U VAL : 0x00000000U - // .. L3_SEL = 0 - // .. ==> 0XF8000730[7:5] = 0x00000000U - // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000730[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U // .. 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 + // .. PULLUP = 1 + // .. ==> 0XF8000730[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U // .. DisableRcvr = 0 // .. ==> 0XF8000730[13:13] = 0x00000000U // .. ==> MASK : 0x00002000U VAL : 0x00000000U // .. - EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00000600U), + EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00001640U), // .. TRI_ENABLE = 0 // .. ==> 0XF8000734[0:0] = 0x00000000U // .. ==> MASK : 0x00000001U VAL : 0x00000000U @@ -2541,23 +2541,23 @@ unsigned long ps7_mio_init_data_1_0[] = { // .. L2_SEL = 0 // .. ==> 0XF8000734[4:3] = 0x00000000U // .. ==> MASK : 0x00000018U VAL : 0x00000000U - // .. L3_SEL = 0 - // .. ==> 0XF8000734[7:5] = 0x00000000U - // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000734[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U // .. 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 + // .. PULLUP = 1 + // .. ==> 0XF8000734[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U // .. DisableRcvr = 0 // .. ==> 0XF8000734[13:13] = 0x00000000U // .. ==> MASK : 0x00002000U VAL : 0x00000000U // .. - EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00000600U), + EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00001640U), // .. TRI_ENABLE = 0 // .. ==> 0XF8000738[0:0] = 0x00000000U // .. ==> MASK : 0x00000001U VAL : 0x00000000U @@ -3767,16 +3767,16 @@ unsigned long ps7_peripherals_init_data_1_0[] = { // .. START: SRAM/NOR SET OPMODE // .. FINISH: SRAM/NOR SET OPMODE // .. START: UART REGISTERS - // .. BDIV = 0x5 - // .. ==> 0XE0001034[7:0] = 0x00000005U - // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. BDIV = 0x6 + // .. ==> 0XE0001034[7:0] = 0x00000006U + // .. ==> MASK : 0x000000FFU VAL : 0x00000006U // .. - EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000005U), - // .. CD = 0x9 - // .. ==> 0XE0001018[15:0] = 0x00000009U - // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000006U), + // .. CD = 0x3e + // .. ==> 0XE0001018[15:0] = 0x0000003EU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000003EU // .. - EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x00000009U), + EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x0000003EU), // .. STPBRK = 0x0 // .. ==> 0XE0001000[8:8] = 0x00000000U // .. ==> MASK : 0x00000100U VAL : 0x00000000U @@ -3829,16 +3829,16 @@ unsigned long ps7_peripherals_init_data_1_0[] = { // .. ==> MASK : 0x00000001U VAL : 0x00000000U // .. EMIT_MASKWRITE(0XE0001004, 0x00000FFFU ,0x00000020U), - // .. BDIV = 0x5 - // .. ==> 0XE0000034[7:0] = 0x00000005U - // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. BDIV = 0x6 + // .. ==> 0XE0000034[7:0] = 0x00000006U + // .. ==> MASK : 0x000000FFU VAL : 0x00000006U // .. - EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000005U), - // .. CD = 0x9 - // .. ==> 0XE0000018[15:0] = 0x00000009U - // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000006U), + // .. CD = 0x3e + // .. ==> 0XE0000018[15:0] = 0x0000003EU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000003EU // .. - EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x00000009U), + EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x0000003EU), // .. STPBRK = 0x0 // .. ==> 0XE0000000[8:8] = 0x00000000U // .. ==> MASK : 0x00000100U VAL : 0x00000000U @@ -6769,23 +6769,23 @@ unsigned long ps7_mio_init_data_2_0[] = { // .. L2_SEL = 0 // .. ==> 0XF8000730[4:3] = 0x00000000U // .. ==> MASK : 0x00000018U VAL : 0x00000000U - // .. L3_SEL = 0 - // .. ==> 0XF8000730[7:5] = 0x00000000U - // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000730[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U // .. 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 + // .. PULLUP = 1 + // .. ==> 0XF8000730[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U // .. DisableRcvr = 0 // .. ==> 0XF8000730[13:13] = 0x00000000U // .. ==> MASK : 0x00002000U VAL : 0x00000000U // .. - EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00000600U), + EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00001640U), // .. TRI_ENABLE = 0 // .. ==> 0XF8000734[0:0] = 0x00000000U // .. ==> MASK : 0x00000001U VAL : 0x00000000U @@ -6798,23 +6798,23 @@ unsigned long ps7_mio_init_data_2_0[] = { // .. L2_SEL = 0 // .. ==> 0XF8000734[4:3] = 0x00000000U // .. ==> MASK : 0x00000018U VAL : 0x00000000U - // .. L3_SEL = 0 - // .. ==> 0XF8000734[7:5] = 0x00000000U - // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000734[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U // .. 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 + // .. PULLUP = 1 + // .. ==> 0XF8000734[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U // .. DisableRcvr = 0 // .. ==> 0XF8000734[13:13] = 0x00000000U // .. ==> MASK : 0x00002000U VAL : 0x00000000U // .. - EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00000600U), + EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00001640U), // .. TRI_ENABLE = 0 // .. ==> 0XF8000738[0:0] = 0x00000000U // .. ==> MASK : 0x00000001U VAL : 0x00000000U @@ -8024,16 +8024,16 @@ unsigned long ps7_peripherals_init_data_2_0[] = { // .. START: SRAM/NOR SET OPMODE // .. FINISH: SRAM/NOR SET OPMODE // .. START: UART REGISTERS - // .. BDIV = 0x5 - // .. ==> 0XE0001034[7:0] = 0x00000005U - // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. BDIV = 0x6 + // .. ==> 0XE0001034[7:0] = 0x00000006U + // .. ==> MASK : 0x000000FFU VAL : 0x00000006U // .. - EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000005U), - // .. CD = 0x9 - // .. ==> 0XE0001018[15:0] = 0x00000009U - // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000006U), + // .. CD = 0x3e + // .. ==> 0XE0001018[15:0] = 0x0000003EU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000003EU // .. - EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x00000009U), + EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x0000003EU), // .. STPBRK = 0x0 // .. ==> 0XE0001000[8:8] = 0x00000000U // .. ==> MASK : 0x00000100U VAL : 0x00000000U @@ -8086,16 +8086,16 @@ unsigned long ps7_peripherals_init_data_2_0[] = { // .. ==> MASK : 0x00000001U VAL : 0x00000000U // .. EMIT_MASKWRITE(0XE0001004, 0x00000FFFU ,0x00000020U), - // .. BDIV = 0x5 - // .. ==> 0XE0000034[7:0] = 0x00000005U - // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. BDIV = 0x6 + // .. ==> 0XE0000034[7:0] = 0x00000006U + // .. ==> MASK : 0x000000FFU VAL : 0x00000006U // .. - EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000005U), - // .. CD = 0x9 - // .. ==> 0XE0000018[15:0] = 0x00000009U - // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000006U), + // .. CD = 0x3e + // .. ==> 0XE0000018[15:0] = 0x0000003EU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000003EU // .. - EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x00000009U), + EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x0000003EU), // .. STPBRK = 0x0 // .. ==> 0XE0000000[8:8] = 0x00000000U // .. ==> MASK : 0x00000100U VAL : 0x00000000U @@ -10716,23 +10716,23 @@ unsigned long ps7_mio_init_data_3_0[] = { // .. L2_SEL = 0 // .. ==> 0XF8000730[4:3] = 0x00000000U // .. ==> MASK : 0x00000018U VAL : 0x00000000U - // .. L3_SEL = 0 - // .. ==> 0XF8000730[7:5] = 0x00000000U - // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000730[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U // .. 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 + // .. PULLUP = 1 + // .. ==> 0XF8000730[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U // .. DisableRcvr = 0 // .. ==> 0XF8000730[13:13] = 0x00000000U // .. ==> MASK : 0x00002000U VAL : 0x00000000U // .. - EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00000600U), + EMIT_MASKWRITE(0XF8000730, 0x00003FFFU ,0x00001640U), // .. TRI_ENABLE = 0 // .. ==> 0XF8000734[0:0] = 0x00000000U // .. ==> MASK : 0x00000001U VAL : 0x00000000U @@ -10745,23 +10745,23 @@ unsigned long ps7_mio_init_data_3_0[] = { // .. L2_SEL = 0 // .. ==> 0XF8000734[4:3] = 0x00000000U // .. ==> MASK : 0x00000018U VAL : 0x00000000U - // .. L3_SEL = 0 - // .. ==> 0XF8000734[7:5] = 0x00000000U - // .. ==> MASK : 0x000000E0U VAL : 0x00000000U + // .. L3_SEL = 2 + // .. ==> 0XF8000734[7:5] = 0x00000002U + // .. ==> MASK : 0x000000E0U VAL : 0x00000040U // .. 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 + // .. PULLUP = 1 + // .. ==> 0XF8000734[12:12] = 0x00000001U + // .. ==> MASK : 0x00001000U VAL : 0x00001000U // .. DisableRcvr = 0 // .. ==> 0XF8000734[13:13] = 0x00000000U // .. ==> MASK : 0x00002000U VAL : 0x00000000U // .. - EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00000600U), + EMIT_MASKWRITE(0XF8000734, 0x00003FFFU ,0x00001640U), // .. TRI_ENABLE = 0 // .. ==> 0XF8000738[0:0] = 0x00000000U // .. ==> MASK : 0x00000001U VAL : 0x00000000U @@ -11971,16 +11971,16 @@ unsigned long ps7_peripherals_init_data_3_0[] = { // .. START: SRAM/NOR SET OPMODE // .. FINISH: SRAM/NOR SET OPMODE // .. START: UART REGISTERS - // .. BDIV = 0x5 - // .. ==> 0XE0001034[7:0] = 0x00000005U - // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. BDIV = 0x6 + // .. ==> 0XE0001034[7:0] = 0x00000006U + // .. ==> MASK : 0x000000FFU VAL : 0x00000006U // .. - EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000005U), - // .. CD = 0x9 - // .. ==> 0XE0001018[15:0] = 0x00000009U - // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + EMIT_MASKWRITE(0XE0001034, 0x000000FFU ,0x00000006U), + // .. CD = 0x3e + // .. ==> 0XE0001018[15:0] = 0x0000003EU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000003EU // .. - EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x00000009U), + EMIT_MASKWRITE(0XE0001018, 0x0000FFFFU ,0x0000003EU), // .. STPBRK = 0x0 // .. ==> 0XE0001000[8:8] = 0x00000000U // .. ==> MASK : 0x00000100U VAL : 0x00000000U @@ -12027,16 +12027,16 @@ unsigned long ps7_peripherals_init_data_3_0[] = { // .. ==> MASK : 0x00000001U VAL : 0x00000000U // .. EMIT_MASKWRITE(0XE0001004, 0x000003FFU ,0x00000020U), - // .. BDIV = 0x5 - // .. ==> 0XE0000034[7:0] = 0x00000005U - // .. ==> MASK : 0x000000FFU VAL : 0x00000005U + // .. BDIV = 0x6 + // .. ==> 0XE0000034[7:0] = 0x00000006U + // .. ==> MASK : 0x000000FFU VAL : 0x00000006U // .. - EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000005U), - // .. CD = 0x9 - // .. ==> 0XE0000018[15:0] = 0x00000009U - // .. ==> MASK : 0x0000FFFFU VAL : 0x00000009U + EMIT_MASKWRITE(0XE0000034, 0x000000FFU ,0x00000006U), + // .. CD = 0x3e + // .. ==> 0XE0000018[15:0] = 0x0000003EU + // .. ==> MASK : 0x0000FFFFU VAL : 0x0000003EU // .. - EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x00000009U), + EMIT_MASKWRITE(0XE0000018, 0x0000FFFFU ,0x0000003EU), // .. STPBRK = 0x0 // .. ==> 0XE0000000[8:8] = 0x00000000U // .. ==> MASK : 0x00000100U VAL : 0x00000000U diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.html b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.html deleted file mode 100644 index e6b1a8a0bce3b9ebe7cfc4bd0e8469efb313d716..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.html +++ /dev/null @@ -1,8860 +0,0 @@ -<!DOCTYPE html> -<html lang="en"> -<head> -<meta http-equiv="content-type" content="text/html;charset=UTF-8"/> -<title>Zynq PS configuration detail</title> -<style type="text/css"> -.hex {font-family:monospace ; text-align : right} -td { min-width : 80px ; } -</style> -</head> -<body> -<p style="height: 7px">Following peripherals are selected in the design. </p> -<p><br /></p> -<h2><a name="Top">Peripheral Selected</a></h2> -<ul> -<li>Quad SPI Flash</li> -<li>Enet 0</li> -<li>USB 0</li> -<li>SD 0</li> -<li>UART 0</li> -<li>UART 1</li> -<li>I2C 0</li> -<li>I2C 1</li> -<li>GPIO</li> -</ul> -<p>To see detailed information please follow below links:</p> -<ul> -<li><a href="#MIOConfTab">MIO Configuration Table</a></li> -<li><a href="#ZynqPerTab">Zynq Peripheral Configuration</a></li> -<li><a href="#DDRInfoTab">DDR Configuration Information</a></li> -<li>SLCR settings</li> -<ul> -<li><a href="#ps7_pll_init_data">PLL Init Data</a></li> -<li><a href="#ps7_clock_init_data">Clock Init Data</a></li> -<li><a href="#ps7_ddr_init_data">DDR Init Data</a></li> -<li><a href="#ps7_mio_init_data">MIO Init Data</a></li> -</ul> -</ul> -<h2><a name="MIOConfTab">MIO configuration Table</a></h2> -<ul><table border="1"> -<thead><tr> <th>MIO Pin</th> <th>Peripheral</th> <th>Signal</th> <th>IO type</th> <th>Speed</th> <th>Pullup</th> <th>Direction</th> </tr></thead> -<tr bgcolor="#FA4A46"><td><a name="MIO 0">MIO 0</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[0]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 1">MIO 1</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_ss_b</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 2">MIO 2</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[0]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 3">MIO 3</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[1]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 4">MIO 4</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[2]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 5">MIO 5</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[3]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 6">MIO 6</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_sclk</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 7">MIO 7</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[7]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 8">MIO 8</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi_fbclk</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 9">MIO 9</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[9]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 10">MIO 10</a></td><td><a href="#I2C 0">I2C 0</a></td><td>scl</td><td>LVCMOS 3.3V</td><td>slow</td><td>enabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 11">MIO 11</a></td><td><a href="#I2C 0">I2C 0</a></td><td>sda</td><td>LVCMOS 3.3V</td><td>slow</td><td>enabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 12">MIO 12</a></td><td><a href="#I2C 1">I2C 1</a></td><td>scl</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 13">MIO 13</a></td><td><a href="#I2C 1">I2C 1</a></td><td>sda</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 14">MIO 14</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[14]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 15">MIO 15</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[15]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 16">MIO 16</a></td><td><a href="#Enet 0">Enet 0</a></td><td>tx_clk</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 17">MIO 17</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[0]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 18">MIO 18</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[1]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 19">MIO 19</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[2]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 20">MIO 20</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[3]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 21">MIO 21</a></td><td><a href="#Enet 0">Enet 0</a></td><td>tx_ctl</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 22">MIO 22</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rx_clk</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 23">MIO 23</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[0]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 24">MIO 24</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[1]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 25">MIO 25</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[2]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 26">MIO 26</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[3]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 27">MIO 27</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rx_ctl</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 28">MIO 28</a></td><td><a href="#USB 0">USB 0</a></td><td>data[4]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 29">MIO 29</a></td><td><a href="#USB 0">USB 0</a></td><td>dir</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 30">MIO 30</a></td><td><a href="#USB 0">USB 0</a></td><td>stp</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 31">MIO 31</a></td><td><a href="#USB 0">USB 0</a></td><td>nxt</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 32">MIO 32</a></td><td><a href="#USB 0">USB 0</a></td><td>data[0]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 33">MIO 33</a></td><td><a href="#USB 0">USB 0</a></td><td>data[1]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 34">MIO 34</a></td><td><a href="#USB 0">USB 0</a></td><td>data[2]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 35">MIO 35</a></td><td><a href="#USB 0">USB 0</a></td><td>data[3]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 36">MIO 36</a></td><td><a href="#USB 0">USB 0</a></td><td>clk</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 37">MIO 37</a></td><td><a href="#USB 0">USB 0</a></td><td>data[5]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 38">MIO 38</a></td><td><a href="#USB 0">USB 0</a></td><td>data[6]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 39">MIO 39</a></td><td><a href="#USB 0">USB 0</a></td><td>data[7]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 40">MIO 40</a></td><td><a href="#SD 0">SD 0</a></td><td>clk</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 41">MIO 41</a></td><td><a href="#SD 0">SD 0</a></td><td>cmd</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 42">MIO 42</a></td><td><a href="#SD 0">SD 0</a></td><td>data[0]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 43">MIO 43</a></td><td><a href="#SD 0">SD 0</a></td><td>data[1]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 44">MIO 44</a></td><td><a href="#SD 0">SD 0</a></td><td>data[2]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 45">MIO 45</a></td><td><a href="#SD 0">SD 0</a></td><td>data[3]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 46">MIO 46</a></td><td><a href="#USB 0">USB 0</a></td><td>reset</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 47">MIO 47</a></td><td><a href="#SD 0">SD 0</a></td><td>cd</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#6495ED"><td><a name="MIO 48">MIO 48</a></td><td><a href="#UART 1">UART 1</a></td><td>tx</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#6495ED"><td><a name="MIO 49">MIO 49</a></td><td><a href="#UART 1">UART 1</a></td><td>rx</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 50">MIO 50</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[50]</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 51">MIO 51</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[51]</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 52">MIO 52</a></td><td><a href="#Enet 0">Enet 0</a></td><td>mdc</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 53">MIO 53</a></td><td><a href="#Enet 0">Enet 0</a></td><td>mdio</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h2><a name="ZynqPerTab">Zynq Peripheral Configuration</a></h2> -<ul><table border="1"> -<tr><thead> <th>Peripheral</th> <th>Signal Group</th> <th>Signal</th> <th>MIO</th> </thead></tr> -<tr bgcolor="#FAEBD7"><td><a name="Quad SPI Flash" >Quad SPI Flash</a></td> <td></td><td></td><td>MIO 1 .. 6</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Dual Quad SPI (4 bit) </td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Dual Quad SPI (Parallel 8 bit)</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Feedback Clk</td><td></td><td>MIO 8</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="nor" >SRAM/NOR Flash</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FFE4C4"><td><a name="nand" >NAND Flash</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DEB887"><td><a name="Enet 0" >Enet 0</a></td> <td></td><td></td><td>MIO 16 .. 27</td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>tx_clk</td><td><a href="#MIO 16">MIO 16</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[3]</td><td><a href="#MIO 20">MIO 20</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[2]</td><td><a href="#MIO 19">MIO 19</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[1]</td><td><a href="#MIO 18">MIO 18</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[0]</td><td><a href="#MIO 17">MIO 17</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>tx_ctl</td><td><a href="#MIO 21">MIO 21</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rx_clk</td><td><a href="#MIO 22">MIO 22</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[3]</td><td><a href="#MIO 26">MIO 26</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[2]</td><td><a href="#MIO 25">MIO 25</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[1]</td><td><a href="#MIO 24">MIO 24</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[0]</td><td><a href="#MIO 23">MIO 23</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rx_ctl</td><td><a href="#MIO 27">MIO 27</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td>MDIO</td><td></td><td>MIO 52 .. 53</td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>mdc</td><td><a href="#MIO 52">MIO 52</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>mdio</td><td><a href="#MIO 53">MIO 53</a></td></tr> -<tr bgcolor="#DEB887"><td><a name="enet1" >Enet 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#7FFF00"><td><a name="USB 0" >USB 0</a></td> <td></td><td></td><td>MIO 28 .. 39</td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>clk</td><td><a href="#MIO 36">MIO 36</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>dir</td><td><a href="#MIO 29">MIO 29</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>stp</td><td><a href="#MIO 30">MIO 30</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>nxt</td><td><a href="#MIO 31">MIO 31</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[0]</td><td><a href="#MIO 32">MIO 32</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[1]</td><td><a href="#MIO 33">MIO 33</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[2]</td><td><a href="#MIO 34">MIO 34</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[3]</td><td><a href="#MIO 35">MIO 35</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[4]</td><td><a href="#MIO 28">MIO 28</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[5]</td><td><a href="#MIO 37">MIO 37</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[6]</td><td><a href="#MIO 38">MIO 38</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[7]</td><td><a href="#MIO 39">MIO 39</a></td></tr> -<tr bgcolor="#7FFF00"><td><a name="usb1" >USB 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#D2691E"><td><a name="SD 0" >SD 0</a></td> <td></td><td></td><td>MIO 40 .. 45</td></tr> -<tr bgcolor="#D2691E"><td></td><td>CD</td><td></td><td>MIO 47</td></tr> -<tr bgcolor="#D2691E"><td></td><td>WP</td><td></td><td>EMIO</td></tr> -<tr bgcolor="#D2691E"><td></td><td>Power</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#D2691E"><td><a name="sd1" >SD 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#6495ED"><td><a name="UART 0" >UART 0</a></td> <td></td><td></td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>rx</td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>tx</td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td>Modem signals</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#6495ED"><td><a name="UART 1" >UART 1</a></td> <td></td><td></td><td>MIO 48 .. 49</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>rx</td><td><a href="#MIO 49">MIO 49</a></td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>tx</td><td><a href="#MIO 48">MIO 48</a></td></tr> -<tr bgcolor="#6495ED"><td></td><td>Modem Signals</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BDB76B"><td><a name="I2C 0" >I2C 0</a></td> <td></td><td></td><td>MIO 10 .. 11</td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>scl</td><td><a href="#MIO 10">MIO 10</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>sda</td><td><a href="#MIO 11">MIO 11</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td>Interrupt</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BDB76B"><td><a name="I2C 1" >I2C 1</a></td> <td></td><td></td><td>MIO 12 .. 13</td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>scl</td><td><a href="#MIO 12">MIO 12</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>sda</td><td><a href="#MIO 13">MIO 13</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td>Interrupt</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#8DBC8F"><td><a name="spi0" >SPI 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#8DBC8F"><td><a name="spi1" >SPI 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DAA520"><td><a name="can0" >CAN 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DAA520"><td><a name="can1" >CAN 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#ADD8E6"><td><a name="trace" >Trace</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BC8F8F"><td><a name="ttc0" >Timer 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BC8F8F"><td><a name="ttc1" >Timer 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FF6347"><td><a name="wdt" >Watchdog</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#EE82EE"><td><a name="pjtag" >PJTAG</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FA4A46"><td><a name="GPIO" >GPIO</a></td> <td></td><td></td><td>MIO</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="mode" >Mode</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="vcfg" >VCfg</a></td> <td></td><td></td><td>Disabled</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h2><a name="DDRInfoTab">DDR Memory information</a></h2> -<h3><a name="DDRInfoTab">DDR Controller Configuration</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="Enable DDR">Enable DDR</a></td><td>1</td></tr> -<tr> <td><a name="Memory Type">Memory Type</a></td><td>DDR 3</td></tr> -<tr> <td><a name="Memory Part">Memory Part</a></td><td>MT41K128M16 JT-125</td></tr> -<tr> <td><a name="DRAM bus width">DRAM bus width</a></td><td>32 Bit</td></tr> -<tr> <td><a name="ECC">ECC</a></td><td>Disabled</td></tr> -<tr> <td><a name="BURST Length (lppdr only)">BURST Length (lppdr only)</a></td><td>8</td></tr> -<tr> <td><a name="Internal Vref">Internal Vref</a></td><td>0</td></tr> -<tr> <td><a name="Operating Frequency (MHz)">Operating Frequency (MHz)</a></td><td>525.000000</td></tr> -<tr> <td><a name="HIGH temperature">HIGH temperature</a></td><td>Normal (0-85)</td></tr> -</table></ul> -<h3><a name="DDRInfoTab">Memory Part Configuration</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="DRAM IC bus width">DRAM IC bus width</a></td><td>16 Bits</td></tr> -<tr> <td><a name="DRAM Device Capacity">DRAM Device Capacity</a></td><td>2048 MBits</td></tr> -<tr> <td><a name="Speed Bin">Speed Bin</a></td><td>DDR3_1066F</td></tr> -<tr> <td><a name="BANK Address Count">BANK Address Count</a></td><td>3</td></tr> -<tr> <td><a name="ROW Address Count">ROW Address Count</a></td><td>14</td></tr> -<tr> <td><a name="COLUMN Address Count">COLUMN Address Count</a></td><td>10</td></tr> -<tr> <td><a name="CAS Latency">CAS Latency</a></td><td>7</td></tr> -<tr> <td><a name="CAS Write Latency">CAS Write Latency</a></td><td>6</td></tr> -<tr> <td><a name="RAS to CAS Delay">RAS to CAS Delay</a></td><td>7</td></tr> -<tr> <td><a name="RECHARGE Time">RECHARGE Time</a></td><td>7</td></tr> -<tr> <td><a name="tRC (ns )">tRC (ns )</a></td><td>48.75</td></tr> -<tr> <td><a name="tRASmin ( ns )">tRASmin ( ns )</a></td><td>35.0</td></tr> -<tr> <td><a name="tFAW">tFAW</a></td><td>40.0</td></tr> -<tr> <td><a name="ADDITIVE Latency">ADDITIVE Latency</a></td><td>0</td></tr> -</table></ul> -<h3><a name="DDRInfoTab">Training/Board Details</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="Write levelling">Write levelling</a></td><td>1</td></tr> -<tr> <td><a name="Read gate">Read gate</a></td><td>1</td></tr> -<tr> <td><a name="Read data eye">Read data eye</a></td><td>1</td></tr> -<tr> <td><a name="DQS to Clock delay [0] (ns)">DQS to Clock delay [0] (ns)</a></td><td>-0.073</td></tr> -<tr> <td><a name="DQS to Clock delay [1] (ns)">DQS to Clock delay [1] (ns)</a></td><td>-0.034</td></tr> -<tr> <td><a name="DQS to Clock delay [2] (ns)">DQS to Clock delay [2] (ns)</a></td><td>-0.03</td></tr> -<tr> <td><a name="DQS to Clock delay [3] (ns)">DQS to Clock delay [3] (ns)</a></td><td>-0.082</td></tr> -<tr> <td><a name="Board delay [0] (ns)">Board delay [0] (ns)</a></td><td>0.176</td></tr> -<tr> <td><a name="Board delay [1] (ns)">Board delay [1] (ns)</a></td><td>0.159</td></tr> -<tr> <td><a name="Board delay [2] (ns)">Board delay [2] (ns)</a></td><td>0.162</td></tr> -<tr> <td><a name="Board delay [3] (ns)">Board delay [3] (ns)</a></td><td>0.187</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h1><a name="ps7_pll_init_data_1_0">ps7_pll_init_data_1_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>PLL SLCR REGISTERS</h2> -<ul> -<p>PLL SLCR REGISTERS</p> -<h2>ARM PLL INIT</h2> -<ul> -<p>ARM PLL INIT</p> -<li><p>Register : ARM_PLL_CFG @ 0XF8000110</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">177</td><td class="hex">177000</td></tr> -<tr><td><b>ARM_PLL_CFG @ 0XF8000110</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1772c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">1a</td><td class="hex">1a000</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>1a000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >ARM_PLL_LOCK</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<li><p>Register : ARM_CLK_CTRL @ 0XF8000120</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >CPU_6OR4XCLKACT</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td >CPU_3OR2XCLKACT</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">1</td><td class="hex">2000000</td></tr> -<tr><td >CPU_2XCLKACT</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">1</td><td class="hex">4000000</td></tr> -<tr><td >CPU_1XCLKACT</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">1</td><td class="hex">8000000</td></tr> -<tr><td >CPU_PERI_CLKACT</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td><b>ARM_CLK_CTRL @ 0XF8000120</td><td></td><td class="hex"><b>1f003f30</b></td><td></td><td class="hex"><b>1f000200</b></td></tr></table> -</li> -</ul> -<h2>DDR PLL INIT</h2> -<ul> -<p>DDR PLL INIT</p> -<li><p>Register : DDR_PLL_CFG @ 0XF8000114</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">1db</td><td class="hex">1db000</td></tr> -<tr><td><b>DDR_PLL_CFG @ 0XF8000114</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1db2c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">15</td><td class="hex">15000</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>15000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DDR_PLL_LOCK</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>2</b></td><td></td><td class="hex"><b>2</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<li><p>Register : DDR_CLK_CTRL @ 0XF8000124</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DDR_3XCLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >DDR_2XCLKACT</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DDR_3XCLK_DIVISOR</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td >DDR_2XCLK_DIVISOR</td><td class="hex">31:26</td><td class="hex">fc000000</td><td class="hex">3</td><td class="hex">c000000</td></tr> -<tr><td><b>DDR_CLK_CTRL @ 0XF8000124</td><td></td><td class="hex"><b>fff00003</b></td><td></td><td class="hex"><b>c200003</b></td></tr></table> -</li> -</ul> -<h2>IO PLL INIT</h2> -<ul> -<p>IO PLL INIT</p> -<li><p>Register : IO_PLL_CFG @ 0XF8000118</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">1f4</td><td class="hex">1f4000</td></tr> -<tr><td><b>IO_PLL_CFG @ 0XF8000118</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1f42c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">14</td><td class="hex">14000</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>14000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IO_PLL_LOCK</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>4</b></td><td></td><td class="hex"><b>4</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -</ul> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_clock_init_data_1_0">ps7_clock_init_data_1_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>CLOCK CONTROL SLCR REGISTERS</h2> -<ul> -<p>CLOCK CONTROL SLCR REGISTERS</p> -<li><p>Register : DCI_CLK_CTRL @ 0XF8000128</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">34</td><td class="hex">3400</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td><b>DCI_CLK_CTRL @ 0XF8000128</td><td></td><td class="hex"><b>3f03f01</b></td><td></td><td class="hex"><b>203401</b></td></tr></table> -</li> -<li><p>Register : GEM0_RCLK_CTRL @ 0XF8000138</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>GEM0_RCLK_CTRL @ 0XF8000138</td><td></td><td class="hex"><b>11</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -<li><p>Register : GEM0_CLK_CTRL @ 0XF8000140</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">8</td><td class="hex">800</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>GEM0_CLK_CTRL @ 0XF8000140</td><td></td><td class="hex"><b>3f03f71</b></td><td></td><td class="hex"><b>100801</b></td></tr></table> -</li> -<li><p>Register : LQSPI_CLK_CTRL @ 0XF800014C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">5</td><td class="hex">500</td></tr> -<tr><td><b>LQSPI_CLK_CTRL @ 0XF800014C</td><td></td><td class="hex"><b>3f31</b></td><td></td><td class="hex"><b>501</b></td></tr></table> -</li> -<li><p>Register : SDIO_CLK_CTRL @ 0XF8000150</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT0</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >CLKACT1</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">14</td><td class="hex">1400</td></tr> -<tr><td><b>SDIO_CLK_CTRL @ 0XF8000150</td><td></td><td class="hex"><b>3f33</b></td><td></td><td class="hex"><b>1401</b></td></tr></table> -</li> -<li><p>Register : UART_CLK_CTRL @ 0XF8000154</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT0</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >CLKACT1</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">14</td><td class="hex">1400</td></tr> -<tr><td><b>UART_CLK_CTRL @ 0XF8000154</td><td></td><td class="hex"><b>3f33</b></td><td></td><td class="hex"><b>1403</b></td></tr></table> -</li> -<li><p>Register : PCAP_CLK_CTRL @ 0XF8000168</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">5</td><td class="hex">500</td></tr> -<tr><td><b>PCAP_CLK_CTRL @ 0XF8000168</td><td></td><td class="hex"><b>3f31</b></td><td></td><td class="hex"><b>501</b></td></tr></table> -</li> -<li><p>Register : FPGA0_CLK_CTRL @ 0XF8000170</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">a</td><td class="hex">a00</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA0_CLK_CTRL @ 0XF8000170</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100a00</b></td></tr></table> -</li> -<li><p>Register : FPGA1_CLK_CTRL @ 0XF8000180</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">3</td><td class="hex">30</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">6</td><td class="hex">600</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA1_CLK_CTRL @ 0XF8000180</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100630</b></td></tr></table> -</li> -<li><p>Register : FPGA2_CLK_CTRL @ 0XF8000190</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">2</td><td class="hex">20</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">35</td><td class="hex">3500</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td><b>FPGA2_CLK_CTRL @ 0XF8000190</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>203520</b></td></tr></table> -</li> -<li><p>Register : FPGA3_CLK_CTRL @ 0XF80001A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">a</td><td class="hex">a00</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA3_CLK_CTRL @ 0XF80001A0</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100a00</b></td></tr></table> -</li> -<li><p>Register : CLK_621_TRUE @ 0XF80001C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLK_621_TRUE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>CLK_621_TRUE @ 0XF80001C4</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -<li><p>Register : APER_CLK_CTRL @ 0XF800012C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DMA_CPU_2XCLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >USB0_CPU_1XCLKACT</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >USB1_CPU_1XCLKACT</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >GEM0_CPU_1XCLKACT</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">1</td><td class="hex">40</td></tr> -<tr><td >GEM1_CPU_1XCLKACT</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SDI0_CPU_1XCLKACT</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">1</td><td class="hex">400</td></tr> -<tr><td >SDI1_CPU_1XCLKACT</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SPI0_CPU_1XCLKACT</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SPI1_CPU_1XCLKACT</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CAN0_CPU_1XCLKACT</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CAN1_CPU_1XCLKACT</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >I2C0_CPU_1XCLKACT</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">1</td><td class="hex">40000</td></tr> -<tr><td >I2C1_CPU_1XCLKACT</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td >UART0_CPU_1XCLKACT</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td >UART1_CPU_1XCLKACT</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >GPIO_CPU_1XCLKACT</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">1</td><td class="hex">400000</td></tr> -<tr><td >LQSPI_CPU_1XCLKACT</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">1</td><td class="hex">800000</td></tr> -<tr><td >SMC_CPU_1XCLKACT</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td><b>APER_CLK_CTRL @ 0XF800012C</td><td></td><td class="hex"><b>1ffcccd</b></td><td></td><td class="hex"><b>1fc044d</b></td></tr></table> -</li> -</ul> -<h2>THIS SHOULD BE BLANK</h2> -<ul> -<p>THIS SHOULD BE BLANK</p> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_ddr_init_data_1_0">ps7_ddr_init_data_1_0</a></h1> -<ul> -<h2>DDR INITIALIZATION</h2> -<ul> -<p>DDR INITIALIZATION</p> -<h2>LOCK DDR</h2> -<ul> -<p>LOCK DDR</p> -<li><p>Register : ddrc_ctrl @ 0XF8006000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_soft_rstb</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_powerdown_en</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_data_bus_width</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_burst8_refresh</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rdwr_idle_gap</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_ddrc_dis_rd_bypass</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_act_bypass</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_auto_refresh</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ddrc_ctrl @ 0XF8006000</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>80</b></td></tr></table> -</li> -</ul> -<li><p>Register : Two_rank_cfg @ 0XF8006004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_rfc_nom_x32</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">7f</td><td class="hex">7f</td></tr> -<tr><td >reg_ddrc_active_ranks</td><td class="hex">13:12</td><td class="hex">3000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >reg_ddrc_addrmap_cs_bit0</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_wr_odt_block</td><td class="hex">20:19</td><td class="hex">180000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td >reg_ddrc_diff_rank_rd_2cycle_gap</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_cs_bit1</td><td class="hex">26:22</td><td class="hex">7c00000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_open_bank</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_4bank_ram</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>Two_rank_cfg @ 0XF8006004</td><td></td><td class="hex"><b>1fffffff</b></td><td></td><td class="hex"><b>8107f</b></td></tr></table> -</li> -<li><p>Register : HPR_reg @ 0XF8006008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_hpr_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">f</td><td class="hex">f</td></tr> -<tr><td >reg_ddrc_hpr_max_starve_x32</td><td class="hex">21:11</td><td class="hex">3ff800</td><td class="hex">f</td><td class="hex">7800</td></tr> -<tr><td >reg_ddrc_hpr_xact_run_length</td><td class="hex">25:22</td><td class="hex">3c00000</td><td class="hex">f</td><td class="hex">3c00000</td></tr> -<tr><td><b>HPR_reg @ 0XF8006008</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>3c0780f</b></td></tr></table> -</li> -<li><p>Register : LPR_reg @ 0XF800600C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_lpr_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_lpr_max_starve_x32</td><td class="hex">21:11</td><td class="hex">3ff800</td><td class="hex">2</td><td class="hex">1000</td></tr> -<tr><td >reg_ddrc_lpr_xact_run_length</td><td class="hex">25:22</td><td class="hex">3c00000</td><td class="hex">8</td><td class="hex">2000000</td></tr> -<tr><td><b>LPR_reg @ 0XF800600C</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>2001001</b></td></tr></table> -</li> -<li><p>Register : WR_reg @ 0XF8006010</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_w_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_w_xact_run_length</td><td class="hex">14:11</td><td class="hex">7800</td><td class="hex">8</td><td class="hex">4000</td></tr> -<tr><td >reg_ddrc_w_max_starve_x32</td><td class="hex">25:15</td><td class="hex">3ff8000</td><td class="hex">2</td><td class="hex">10000</td></tr> -<tr><td><b>WR_reg @ 0XF8006010</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>14001</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg0 @ 0XF8006014</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_rc</td><td class="hex">5:0</td><td class="hex">3f</td><td class="hex">1a</td><td class="hex">1a</td></tr> -<tr><td >reg_ddrc_t_rfc_min</td><td class="hex">13:6</td><td class="hex">3fc0</td><td class="hex">54</td><td class="hex">1500</td></tr> -<tr><td >reg_ddrc_post_selfref_gap_x32</td><td class="hex">20:14</td><td class="hex">1fc000</td><td class="hex">10</td><td class="hex">40000</td></tr> -<tr><td><b>DRAM_param_reg0 @ 0XF8006014</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>4151a</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg1 @ 0XF8006018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_wr2pre</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">12</td><td class="hex">12</td></tr> -<tr><td >reg_ddrc_powerdown_to_x32</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">6</td><td class="hex">c0</td></tr> -<tr><td >reg_ddrc_t_faw</td><td class="hex">15:10</td><td class="hex">fc00</td><td class="hex">15</td><td class="hex">5400</td></tr> -<tr><td >reg_ddrc_t_ras_max</td><td class="hex">21:16</td><td class="hex">3f0000</td><td class="hex">23</td><td class="hex">230000</td></tr> -<tr><td >reg_ddrc_t_ras_min</td><td class="hex">26:22</td><td class="hex">7c00000</td><td class="hex">13</td><td class="hex">4c00000</td></tr> -<tr><td >reg_ddrc_t_cke</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">4</td><td class="hex">40000000</td></tr> -<tr><td><b>DRAM_param_reg1 @ 0XF8006018</td><td></td><td class="hex"><b>f7ffffff</b></td><td></td><td class="hex"><b>44e354d2</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg2 @ 0XF800601C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_write_latency</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">5</td><td class="hex">5</td></tr> -<tr><td >reg_ddrc_rd2wr</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >reg_ddrc_wr2rd</td><td class="hex">14:10</td><td class="hex">7c00</td><td class="hex">e</td><td class="hex">3800</td></tr> -<tr><td >reg_ddrc_t_xp</td><td class="hex">19:15</td><td class="hex">f8000</td><td class="hex">4</td><td class="hex">20000</td></tr> -<tr><td >reg_ddrc_pad_pd</td><td class="hex">22:20</td><td class="hex">700000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rd2pre</td><td class="hex">27:23</td><td class="hex">f800000</td><td class="hex">4</td><td class="hex">2000000</td></tr> -<tr><td >reg_ddrc_t_rcd</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">7</td><td class="hex">70000000</td></tr> -<tr><td><b>DRAM_param_reg2 @ 0XF800601C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>720238e5</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg3 @ 0XF8006020</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_ccd</td><td class="hex">4:2</td><td class="hex">1c</td><td class="hex">4</td><td class="hex">10</td></tr> -<tr><td >reg_ddrc_t_rrd</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">6</td><td class="hex">c0</td></tr> -<tr><td >reg_ddrc_refresh_margin</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >reg_ddrc_t_rp</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">7</td><td class="hex">7000</td></tr> -<tr><td >reg_ddrc_refresh_to_x32</td><td class="hex">20:16</td><td class="hex">1f0000</td><td class="hex">8</td><td class="hex">80000</td></tr> -<tr><td >reg_ddrc_sdram</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >reg_ddrc_mobile</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_clock_stop_en</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_read_latency</td><td class="hex">28:24</td><td class="hex">1f000000</td><td class="hex">7</td><td class="hex">7000000</td></tr> -<tr><td >reg_phy_mode_ddr1_ddr2</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">1</td><td class="hex">20000000</td></tr> -<tr><td >reg_ddrc_dis_pad_pd</td><td class="hex">30:30</td><td class="hex">40000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_loopback</td><td class="hex">31:31</td><td class="hex">80000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_param_reg3 @ 0XF8006020</td><td></td><td class="hex"><b>fffffffc</b></td><td></td><td class="hex"><b>272872d0</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg4 @ 0XF8006024</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_en_2t_timing_mode</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_prefer_write</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_max_rank_rd</td><td class="hex">5:2</td><td class="hex">3c</td><td class="hex">f</td><td class="hex">3c</td></tr> -<tr><td >reg_ddrc_mr_wr</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_addr</td><td class="hex">8:7</td><td class="hex">180</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_data</td><td class="hex">24:9</td><td class="hex">1fffe00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ddrc_reg_mr_wr_busy</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_type</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_rdata_valid</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_param_reg4 @ 0XF8006024</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>3c</b></td></tr></table> -</li> -<li><p>Register : DRAM_init_param @ 0XF8006028</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_final_wait_x32</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">7</td><td class="hex">7</td></tr> -<tr><td >reg_ddrc_pre_ocd_x32</td><td class="hex">10:7</td><td class="hex">780</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_t_mrd</td><td class="hex">13:11</td><td class="hex">3800</td><td class="hex">4</td><td class="hex">2000</td></tr> -<tr><td><b>DRAM_init_param @ 0XF8006028</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2007</b></td></tr></table> -</li> -<li><p>Register : DRAM_EMR_reg @ 0XF800602C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_emr2</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">8</td><td class="hex">8</td></tr> -<tr><td >reg_ddrc_emr3</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_EMR_reg @ 0XF800602C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>8</b></td></tr></table> -</li> -<li><p>Register : DRAM_EMR_MR_reg @ 0XF8006030</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_mr</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">930</td><td class="hex">930</td></tr> -<tr><td >reg_ddrc_emr</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">4</td><td class="hex">40000</td></tr> -<tr><td><b>DRAM_EMR_MR_reg @ 0XF8006030</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>40930</b></td></tr></table> -</li> -<li><p>Register : DRAM_burst8_rdwr @ 0XF8006034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_burst_rdwr</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">4</td><td class="hex">4</td></tr> -<tr><td >reg_ddrc_pre_cke_x1024</td><td class="hex">13:4</td><td class="hex">3ff0</td><td class="hex">101</td><td class="hex">1010</td></tr> -<tr><td >reg_ddrc_post_cke_x1024</td><td class="hex">25:16</td><td class="hex">3ff0000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_ddrc_burstchop</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_burst8_rdwr @ 0XF8006034</td><td></td><td class="hex"><b>13ff3fff</b></td><td></td><td class="hex"><b>11014</b></td></tr></table> -</li> -<li><p>Register : DRAM_disable_DQ @ 0XF8006038</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_force_low_pri_n</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_dq</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_debug_mode</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_level_start</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_level_start</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq0_wait_t</td><td class="hex">12:9</td><td class="hex">1e00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_disable_DQ @ 0XF8006038</td><td></td><td class="hex"><b>1fc3</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_bank @ 0XF800603C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_bank_b0</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">7</td><td class="hex">7</td></tr> -<tr><td >reg_ddrc_addrmap_bank_b1</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">7</td><td class="hex">70</td></tr> -<tr><td >reg_ddrc_addrmap_bank_b2</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">7</td><td class="hex">700</td></tr> -<tr><td >reg_ddrc_addrmap_col_b5</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b6</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_addr_map_bank @ 0XF800603C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>777</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_col @ 0XF8006040</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_col_b2</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b3</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b4</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b7</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b8</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b9</td><td class="hex">23:20</td><td class="hex">f00000</td><td class="hex">f</td><td class="hex">f00000</td></tr> -<tr><td >reg_ddrc_addrmap_col_b10</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">f</td><td class="hex">f000000</td></tr> -<tr><td >reg_ddrc_addrmap_col_b11</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">f</td><td class="hex">f0000000</td></tr> -<tr><td><b>DRAM_addr_map_col @ 0XF8006040</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>fff00000</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_row @ 0XF8006044</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_row_b0</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td >reg_ddrc_addrmap_row_b1</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">6</td><td class="hex">60</td></tr> -<tr><td >reg_ddrc_addrmap_row_b2_11</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">6</td><td class="hex">600</td></tr> -<tr><td >reg_ddrc_addrmap_row_b12</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">6</td><td class="hex">6000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b13</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">6</td><td class="hex">60000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b14</td><td class="hex">23:20</td><td class="hex">f00000</td><td class="hex">f</td><td class="hex">f00000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b15</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">f</td><td class="hex">f000000</td></tr> -<tr><td><b>DRAM_addr_map_row @ 0XF8006044</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>ff66666</b></td></tr></table> -</li> -<li><p>Register : DRAM_ODT_reg @ 0XF8006048</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_rank0_rd_odt</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank0_wr_odt</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >reg_ddrc_rank1_rd_odt</td><td class="hex">8:6</td><td class="hex">1c0</td><td class="hex">1</td><td class="hex">40</td></tr> -<tr><td >reg_ddrc_rank1_wr_odt</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >reg_phy_rd_local_odt</td><td class="hex">13:12</td><td class="hex">3000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_local_odt</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">3</td><td class="hex">c000</td></tr> -<tr><td >reg_phy_idle_local_odt</td><td class="hex">17:16</td><td class="hex">30000</td><td class="hex">3</td><td class="hex">30000</td></tr> -<tr><td >reg_ddrc_rank2_rd_odt</td><td class="hex">20:18</td><td class="hex">1c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank2_wr_odt</td><td class="hex">23:21</td><td class="hex">e00000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank3_rd_odt</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank3_wr_odt</td><td class="hex">29:27</td><td class="hex">38000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_ODT_reg @ 0XF8006048</td><td></td><td class="hex"><b>3fffffff</b></td><td></td><td class="hex"><b>3c248</b></td></tr></table> -</li> -<li><p>Register : phy_cmd_timeout_rddata_cpt @ 0XF8006050</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_cmd_to_data</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_cmd_to_data</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rdc_we_to_re_delay</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">8</td><td class="hex">800</td></tr> -<tr><td >reg_phy_rdc_fifo_rst_disable</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_use_fixed_re</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_phy_rdc_fifo_rst_err_cnt_clr</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dis_phy_ctrl_rstn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_clk_stall_level</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_num_of_dq0</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">7</td><td class="hex">7000000</td></tr> -<tr><td >reg_phy_wrlvl_num_of_dq0</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">7</td><td class="hex">70000000</td></tr> -<tr><td><b>phy_cmd_timeout_rddata_cpt @ 0XF8006050</td><td></td><td class="hex"><b>ff0f8fff</b></td><td></td><td class="hex"><b>77010800</b></td></tr></table> -</li> -<li><p>Register : DLL_calib @ 0XF8006058</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dll_calib_to_min_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_dll_calib_to_max_x1024</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >reg_ddrc_dis_dll_calib</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DLL_calib @ 0XF8006058</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>101</b></td></tr></table> -</li> -<li><p>Register : ODT_delay_hold @ 0XF800605C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_rd_odt_delay</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">3</td><td class="hex">3</td></tr> -<tr><td >reg_ddrc_wr_odt_delay</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rd_odt_hold</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_wr_odt_hold</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">5</td><td class="hex">5000</td></tr> -<tr><td><b>ODT_delay_hold @ 0XF800605C</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>5003</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg1 @ 0XF8006060</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_pageclose</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_lpr_num_entries</td><td class="hex">6:1</td><td class="hex">7e</td><td class="hex">1f</td><td class="hex">3e</td></tr> -<tr><td >reg_ddrc_auto_pre_en</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_refresh_update_level</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_wc</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_collision_page_opt</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_selfref_en</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ctrl_reg1 @ 0XF8006060</td><td></td><td class="hex"><b>17ff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg2 @ 0XF8006064</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_go2critical_hysteresis</td><td class="hex">12:5</td><td class="hex">1fe0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_go2critical_en</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">1</td><td class="hex">20000</td></tr> -<tr><td><b>ctrl_reg2 @ 0XF8006064</td><td></td><td class="hex"><b>21fe0</b></td><td></td><td class="hex"><b>20000</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg3 @ 0XF8006068</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_wrlvl_ww</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">41</td><td class="hex">41</td></tr> -<tr><td >reg_ddrc_rdlvl_rr</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">41</td><td class="hex">4100</td></tr> -<tr><td >reg_ddrc_dfi_t_wlmrd</td><td class="hex">25:16</td><td class="hex">3ff0000</td><td class="hex">28</td><td class="hex">280000</td></tr> -<tr><td><b>ctrl_reg3 @ 0XF8006068</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>284141</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg4 @ 0XF800606C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >dfi_t_ctrlupd_interval_min_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">10</td><td class="hex">10</td></tr> -<tr><td >dfi_t_ctrlupd_interval_max_x1024</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">16</td><td class="hex">1600</td></tr> -<tr><td><b>ctrl_reg4 @ 0XF800606C</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>1610</b></td></tr></table> -</li> -<li><p>Register : CHE_REFRESH_TIMER01 @ 0XF80060A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >refresh_timer0_start_value_x32</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >refresh_timer1_start_value_x32</td><td class="hex">23:12</td><td class="hex">fff000</td><td class="hex">8</td><td class="hex">8000</td></tr> -<tr><td><b>CHE_REFRESH_TIMER01 @ 0XF80060A0</td><td></td><td class="hex"><b>ffffff</b></td><td></td><td class="hex"><b>8000</b></td></tr></table> -</li> -<li><p>Register : CHE_T_ZQ @ 0XF80060A4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dis_auto_zq</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_ddr3</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >reg_ddrc_t_mod</td><td class="hex">11:2</td><td class="hex">ffc</td><td class="hex">200</td><td class="hex">800</td></tr> -<tr><td >reg_ddrc_t_zq_long_nop</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">200</td><td class="hex">200000</td></tr> -<tr><td >reg_ddrc_t_zq_short_nop</td><td class="hex">31:22</td><td class="hex">ffc00000</td><td class="hex">40</td><td class="hex">10000000</td></tr> -<tr><td><b>CHE_T_ZQ @ 0XF80060A4</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>10200802</b></td></tr></table> -</li> -<li><p>Register : CHE_T_ZQ_Short_Interval_Reg @ 0XF80060A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >t_zq_short_interval_x1024</td><td class="hex">19:0</td><td class="hex">fffff</td><td class="hex">c845</td><td class="hex">c845</td></tr> -<tr><td >dram_rstn_x1024</td><td class="hex">27:20</td><td class="hex">ff00000</td><td class="hex">67</td><td class="hex">6700000</td></tr> -<tr><td><b>CHE_T_ZQ_Short_Interval_Reg @ 0XF80060A8</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>670c845</b></td></tr></table> -</li> -<li><p>Register : deep_pwrdwn_reg @ 0XF80060AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >deeppowerdown_en</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >deeppowerdown_to_x1024</td><td class="hex">8:1</td><td class="hex">1fe</td><td class="hex">ff</td><td class="hex">1fe</td></tr> -<tr><td><b>deep_pwrdwn_reg @ 0XF80060AC</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>1fe</b></td></tr></table> -</li> -<li><p>Register : reg_2c @ 0XF80060B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >dfi_wrlvl_max_x1024</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">fff</td><td class="hex">fff</td></tr> -<tr><td >dfi_rdlvl_max_x1024</td><td class="hex">23:12</td><td class="hex">fff000</td><td class="hex">fff</td><td class="hex">fff000</td></tr> -<tr><td >ddrc_reg_twrlvl_max_error</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ddrc_reg_trdlvl_max_error</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dfi_wr_level_en</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">1</td><td class="hex">4000000</td></tr> -<tr><td >reg_ddrc_dfi_rd_dqs_gate_level</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">1</td><td class="hex">8000000</td></tr> -<tr><td >reg_ddrc_dfi_rd_data_eye_train</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td><b>reg_2c @ 0XF80060B0</td><td></td><td class="hex"><b>1fffffff</b></td><td></td><td class="hex"><b>1cffffff</b></td></tr></table> -</li> -<li><p>Register : reg_2d @ 0XF80060B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_2t_delay</td><td class="hex">8:0</td><td class="hex">1ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_skip_ocd</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >reg_ddrc_dis_pre_bypass</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_2d @ 0XF80060B4</td><td></td><td class="hex"><b>7ff</b></td><td></td><td class="hex"><b>200</b></td></tr></table> -</li> -<li><p>Register : dfi_timing @ 0XF80060B8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dfi_t_rddata_en</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td >reg_ddrc_dfi_t_ctrlup_min</td><td class="hex">14:5</td><td class="hex">7fe0</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >reg_ddrc_dfi_t_ctrlup_max</td><td class="hex">24:15</td><td class="hex">1ff8000</td><td class="hex">40</td><td class="hex">200000</td></tr> -<tr><td><b>dfi_timing @ 0XF80060B8</td><td></td><td class="hex"><b>1ffffff</b></td><td></td><td class="hex"><b>200066</b></td></tr></table> -</li> -<li><p>Register : CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Clear_Uncorrectable_DRAM_ECC_error</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >Clear_Correctable_DRAM_ECC_error</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td><b>CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</td><td></td><td class="hex"><b>3</b></td><td></td><td class="hex"><b>3</b></td></tr></table> -</li> -</ul> -<li><p>Register : CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Clear_Uncorrectable_DRAM_ECC_error</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Clear_Correctable_DRAM_ECC_error</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</td><td></td><td class="hex"><b>3</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_CORR_ECC_LOG_REG_OFFSET @ 0XF80060C8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CORR_ECC_LOG_VALID</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ECC_CORRECTED_BIT_NUM</td><td class="hex">7:1</td><td class="hex">fe</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_CORR_ECC_LOG_REG_OFFSET @ 0XF80060C8</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_UNCORR_ECC_LOG_REG_OFFSET @ 0XF80060DC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNCORR_ECC_LOG_VALID</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_UNCORR_ECC_LOG_REG_OFFSET @ 0XF80060DC</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_ECC_STATS_REG_OFFSET @ 0XF80060F0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STAT_NUM_CORR_ERR</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STAT_NUM_UNCORR_ERR</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_ECC_STATS_REG_OFFSET @ 0XF80060F0</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : ECC_scrub @ 0XF80060F4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_ecc_mode</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_scrub</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td><b>ECC_scrub @ 0XF80060F4</td><td></td><td class="hex"><b>f</b></td><td></td><td class="hex"><b>8</b></td></tr></table> -</li> -<li><p>Register : phy_rcvr_enable @ 0XF8006114</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_dif_on</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dif_off</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rcvr_enable @ 0XF8006114</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF8006118</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF8006118</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF800611C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF800611C</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF8006120</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF8006120</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF8006124</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF8006124</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF800612C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8f</td><td class="hex">23c00</td></tr> -<tr><td><b>phy_init_ratio @ 0XF800612C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>23c00</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF8006130</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8a</td><td class="hex">22800</td></tr> -<tr><td><b>phy_init_ratio @ 0XF8006130</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>22800</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF8006134</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8b</td><td class="hex">22c00</td></tr> -<tr><td><b>phy_init_ratio @ 0XF8006134</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>22c00</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF8006138</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">92</td><td class="hex">24800</td></tr> -<tr><td><b>phy_init_ratio @ 0XF8006138</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>24800</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF8006140</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF8006140</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF8006144</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF8006144</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF8006148</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF8006148</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF800614C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF800614C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF8006154</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">77</td><td class="hex">77</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF8006154</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>77</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF8006158</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">7c</td><td class="hex">7c</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF8006158</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>7c</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF800615C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">7c</td><td class="hex">7c</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF800615C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>7c</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF8006160</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">75</td><td class="hex">75</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF8006160</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>75</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF8006168</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e4</td><td class="hex">e4</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF8006168</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e4</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF800616C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">df</td><td class="hex">df</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF800616C</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>df</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF8006170</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e0</td><td class="hex">e0</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF8006170</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e0</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF8006174</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e7</td><td class="hex">e7</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF8006174</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e7</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF800617C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">b7</td><td class="hex">b7</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF800617C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>b7</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF8006180</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">bc</td><td class="hex">bc</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF8006180</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>bc</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF8006184</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">bc</td><td class="hex">bc</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF8006184</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>bc</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF8006188</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">b5</td><td class="hex">b5</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF8006188</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>b5</b></td></tr></table> -</li> -<li><p>Register : reg_64 @ 0XF8006190</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_loopback</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bl2</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_at_spd_atpg</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_enable</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_force_err</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_mode</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_invert_clkout</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_phy_all_dq_mpr_rd_resp</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_sel_logic</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">100</td><td class="hex">40000</td></tr> -<tr><td >reg_phy_ctrl_slave_force</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_delay</td><td class="hex">27:21</td><td class="hex">fe00000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_use_rank0_delays</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td >reg_phy_lpddr</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_cmd_latency</td><td class="hex">30:30</td><td class="hex">40000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_int_lpbk</td><td class="hex">31:31</td><td class="hex">80000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_64 @ 0XF8006190</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>10040080</b></td></tr></table> -</li> -<li><p>Register : reg_65 @ 0XF8006194</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_rl_delay</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">2</td><td class="hex">2</td></tr> -<tr><td >reg_phy_rd_rl_delay</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >reg_phy_dll_lock_diff</td><td class="hex">13:10</td><td class="hex">3c00</td><td class="hex">f</td><td class="hex">3c00</td></tr> -<tr><td >reg_phy_use_wr_level</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">1</td><td class="hex">4000</td></tr> -<tr><td >reg_phy_use_rd_dqs_gate_level</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">1</td><td class="hex">8000</td></tr> -<tr><td >reg_phy_use_rd_data_eye_level</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_phy_dis_calib_rst</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_delay</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_65 @ 0XF8006194</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>1fc82</b></td></tr></table> -</li> -<li><p>Register : page_mask @ 0XF8006204</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_page_addr_mask</td><td class="hex">31:0</td><td class="hex">ffffffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>page_mask @ 0XF8006204</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF8006208</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF8006208</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF800620C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF800620C</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF8006210</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF8006210</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF8006214</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF8006214</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF8006218</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF8006218</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF800621C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF800621C</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF8006220</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF8006220</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF8006224</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF8006224</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl0 @ 0XF80062A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_lpddr2</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_per_bank_refresh</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_derate_enable</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr4_margin</td><td class="hex">11:4</td><td class="hex">ff0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>lpddr_ctrl0 @ 0XF80062A8</td><td></td><td class="hex"><b>ff7</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl1 @ 0XF80062AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_mr4_read_interval</td><td class="hex">31:0</td><td class="hex">ffffffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>lpddr_ctrl1 @ 0XF80062AC</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl2 @ 0XF80062B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_min_stable_clock_x1</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">5</td><td class="hex">5</td></tr> -<tr><td >reg_ddrc_idle_after_reset_x32</td><td class="hex">11:4</td><td class="hex">ff0</td><td class="hex">12</td><td class="hex">120</td></tr> -<tr><td >reg_ddrc_t_mrw</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">5</td><td class="hex">5000</td></tr> -<tr><td><b>lpddr_ctrl2 @ 0XF80062B0</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>5125</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl3 @ 0XF80062B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_max_auto_init_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">a6</td><td class="hex">a6</td></tr> -<tr><td >reg_ddrc_dev_zqinit_x32</td><td class="hex">17:8</td><td class="hex">3ff00</td><td class="hex">12</td><td class="hex">1200</td></tr> -<tr><td><b>lpddr_ctrl3 @ 0XF80062B4</td><td></td><td class="hex"><b>3ffff</b></td><td></td><td class="hex"><b>12a6</b></td></tr></table> -</li> -<h2>POLL ON DCI STATUS</h2> -<ul> -<p>POLL ON DCI STATUS</p> -<li><p>Register : DDRIOB_DCI_STATUS @ 0XF8000B74</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DONE</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>DDRIOB_DCI_STATUS @ 0XF8000B74</td><td></td><td class="hex"><b>2000</b></td><td></td><td class="hex"><b>2000</b></td></tr></table> -</li> -</ul> -<h2>UNLOCK DDR</h2> -<ul> -<p>UNLOCK DDR</p> -<li><p>Register : ddrc_ctrl @ 0XF8006000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_soft_rstb</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_powerdown_en</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_data_bus_width</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_burst8_refresh</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rdwr_idle_gap</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_ddrc_dis_rd_bypass</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_act_bypass</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_auto_refresh</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ddrc_ctrl @ 0XF8006000</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>81</b></td></tr></table> -</li> -</ul> -<h2>CHECK DDR STATUS</h2> -<ul> -<p>CHECK DDR STATUS</p> -<li><p>Register : mode_sts_reg @ 0XF8006054</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >ddrc_reg_operating_mode</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>mode_sts_reg @ 0XF8006054</td><td></td><td class="hex"><b>7</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_mio_init_data_1_0">ps7_mio_init_data_1_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>OCM REMAPPING</h2> -<ul> -<p>OCM REMAPPING</p> -<li><p>Register : GPIOB_CTRL @ 0XF8000B00</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >VREF_EN</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >VREF_PULLUP_EN</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLK_PULLUP_EN</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SRSTN_PULLUP_EN</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>GPIOB_CTRL @ 0XF8000B00</td><td></td><td class="hex"><b>303</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DDRIOB SETTINGS</h2> -<ul> -<p>DDRIOB SETTINGS</p> -<li><p>Register : DDRIOB_ADDR0 @ 0XF8000B40</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_ADDR0 @ 0XF8000B40</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_ADDR1 @ 0XF8000B44</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_ADDR1 @ 0XF8000B44</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA0 @ 0XF8000B48</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DATA0 @ 0XF8000B48</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>672</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA1 @ 0XF8000B4C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DATA1 @ 0XF8000B4C</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>672</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF0 @ 0XF8000B50</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">2</td><td class="hex">4</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DIFF0 @ 0XF8000B50</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>674</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF1 @ 0XF8000B54</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">2</td><td class="hex">4</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DIFF1 @ 0XF8000B54</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>674</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_CLOCK @ 0XF8000B58</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_CLOCK @ 0XF8000B58</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_ADDR @ 0XF8000B5C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">1a</td><td class="hex">68000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1a</td><td class="hex">d00000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_ADDR @ 0XF8000B5C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>d6861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_DATA @ 0XF8000B60</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">6</td><td class="hex">18000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1f</td><td class="hex">f80000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_DATA @ 0XF8000B60</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>f9861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_DIFF @ 0XF8000B64</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">6</td><td class="hex">18000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1f</td><td class="hex">f80000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_DIFF @ 0XF8000B64</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>f9861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_CLOCK @ 0XF8000B68</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">1a</td><td class="hex">68000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1a</td><td class="hex">d00000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_CLOCK @ 0XF8000B68</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>d6861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DDR_CTRL @ 0XF8000B6C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >VREF_INT_EN</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VREF_SEL</td><td class="hex">4:1</td><td class="hex">1e</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VREF_EXT_EN</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >VREF_PULLUP_EN</td><td class="hex">8:7</td><td class="hex">180</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >REFIO_EN</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >REFIO_PULLUP_EN</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DRST_B_PULLUP_EN</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CKE_PULLUP_EN</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DDR_CTRL @ 0XF8000B6C</td><td></td><td class="hex"><b>73ff</b></td><td></td><td class="hex"><b>260</b></td></tr></table> -</li> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >VRN_OUT</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">1</td><td class="hex">20</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>21</b></td><td></td><td class="hex"><b>21</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRN_OUT</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">1</td><td class="hex">20</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>21</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -</ul> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >ENABLE</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >VRP_TRI</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRN_TRI</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRP_OUT</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRN_OUT</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">1</td><td class="hex">20</td></tr> -<tr><td >NREF_OPT1</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NREF_OPT2</td><td class="hex">10:8</td><td class="hex">700</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NREF_OPT4</td><td class="hex">13:11</td><td class="hex">3800</td><td class="hex">1</td><td class="hex">800</td></tr> -<tr><td >PREF_OPT1</td><td class="hex">16:14</td><td class="hex">1c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PREF_OPT2</td><td class="hex">19:17</td><td class="hex">e0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >UPDATE_CONTROL</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INIT_COMPLETE</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_CLK</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_HLN</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_HLP</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_RST</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INT_DCI_EN</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>7ffffff</b></td><td></td><td class="hex"><b>823</b></td></tr></table> -</li> -</ul> -<h2>MIO PROGRAMMING</h2> -<ul> -<p>MIO PROGRAMMING</p> -<li><p>Register : MIO_PIN_00 @ 0XF8000700</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_00 @ 0XF8000700</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_01 @ 0XF8000704</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_01 @ 0XF8000704</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_02 @ 0XF8000708</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_02 @ 0XF8000708</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_03 @ 0XF800070C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_03 @ 0XF800070C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_04 @ 0XF8000710</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_04 @ 0XF8000710</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_05 @ 0XF8000714</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_05 @ 0XF8000714</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_06 @ 0XF8000718</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_06 @ 0XF8000718</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_07 @ 0XF800071C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_07 @ 0XF800071C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_08 @ 0XF8000720</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_08 @ 0XF8000720</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_09 @ 0XF8000724</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_09 @ 0XF8000724</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_10 @ 0XF8000728</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_10 @ 0XF8000728</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>1640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_11 @ 0XF800072C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_11 @ 0XF800072C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>1640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_12 @ 0XF8000730</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_12 @ 0XF8000730</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_13 @ 0XF8000734</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_13 @ 0XF8000734</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_14 @ 0XF8000738</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_14 @ 0XF8000738</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_15 @ 0XF800073C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_15 @ 0XF800073C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_16 @ 0XF8000740</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_16 @ 0XF8000740</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_17 @ 0XF8000744</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_17 @ 0XF8000744</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_18 @ 0XF8000748</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_18 @ 0XF8000748</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_19 @ 0XF800074C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_19 @ 0XF800074C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_20 @ 0XF8000750</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_20 @ 0XF8000750</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_21 @ 0XF8000754</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_21 @ 0XF8000754</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_22 @ 0XF8000758</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_22 @ 0XF8000758</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_23 @ 0XF800075C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_23 @ 0XF800075C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_24 @ 0XF8000760</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_24 @ 0XF8000760</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_25 @ 0XF8000764</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_25 @ 0XF8000764</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_26 @ 0XF8000768</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_26 @ 0XF8000768</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_27 @ 0XF800076C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_27 @ 0XF800076C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_28 @ 0XF8000770</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_28 @ 0XF8000770</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_29 @ 0XF8000774</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_29 @ 0XF8000774</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_30 @ 0XF8000778</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_30 @ 0XF8000778</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_31 @ 0XF800077C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_31 @ 0XF800077C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_32 @ 0XF8000780</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_32 @ 0XF8000780</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_33 @ 0XF8000784</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_33 @ 0XF8000784</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_34 @ 0XF8000788</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_34 @ 0XF8000788</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_35 @ 0XF800078C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_35 @ 0XF800078C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_36 @ 0XF8000790</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_36 @ 0XF8000790</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_37 @ 0XF8000794</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_37 @ 0XF8000794</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_38 @ 0XF8000798</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_38 @ 0XF8000798</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_39 @ 0XF800079C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_39 @ 0XF800079C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_40 @ 0XF80007A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_40 @ 0XF80007A0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_41 @ 0XF80007A4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_41 @ 0XF80007A4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_42 @ 0XF80007A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_42 @ 0XF80007A8</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_43 @ 0XF80007AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_43 @ 0XF80007AC</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_44 @ 0XF80007B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_44 @ 0XF80007B0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_45 @ 0XF80007B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_45 @ 0XF80007B4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_46 @ 0XF80007B8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_46 @ 0XF80007B8</td><td></td><td class="hex"><b>3f01</b></td><td></td><td class="hex"><b>200</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_47 @ 0XF80007BC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_47 @ 0XF80007BC</td><td></td><td class="hex"><b>3f01</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_48 @ 0XF80007C0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_48 @ 0XF80007C0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2e0</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_49 @ 0XF80007C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_49 @ 0XF80007C4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2e1</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_50 @ 0XF80007C8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_50 @ 0XF80007C8</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_51 @ 0XF80007CC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_51 @ 0XF80007CC</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_52 @ 0XF80007D0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_52 @ 0XF80007D0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>280</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_53 @ 0XF80007D4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_53 @ 0XF80007D4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>280</b></td></tr></table> -</li> -<li><p>Register : SD0_WP_CD_SEL @ 0XF8000830</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SDIO0_CD_SEL</td><td class="hex">21:16</td><td class="hex">3f0000</td><td class="hex">2f</td><td class="hex">2f0000</td></tr> -<tr><td><b>SD0_WP_CD_SEL @ 0XF8000830</td><td></td><td class="hex"><b>3f0000</b></td><td></td><td class="hex"><b>2f0000</b></td></tr></table> -</li> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_peripherals_init_data_1_0">ps7_peripherals_init_data_1_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>DDR TERM/IBUF_DISABLE_MODE SETTINGS</h2> -<ul> -<p>DDR TERM/IBUF_DISABLE_MODE SETTINGS</p> -<li><p>Register : DDRIOB_DATA0 @ 0XF8000B48</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DATA0 @ 0XF8000B48</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA1 @ 0XF8000B4C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DATA1 @ 0XF8000B4C</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF0 @ 0XF8000B50</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DIFF0 @ 0XF8000B50</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF1 @ 0XF8000B54</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DIFF1 @ 0XF8000B54</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -<h2>SRAM/NOR SET OPMODE</h2> -<ul> -<p>SRAM/NOR SET OPMODE</p> -</ul> -<h2>UART REGISTERS</h2> -<ul> -<p>UART REGISTERS</p> -<li><p>Register : Baud_rate_divider_reg0 @ 0XE0001034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >BDIV</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td><b>Baud_rate_divider_reg0 @ 0XE0001034</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>6</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_gen_reg0 @ 0XE0001018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CD</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">3e</td><td class="hex">3e</td></tr> -<tr><td><b>Baud_rate_gen_reg0 @ 0XE0001018</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : Control_reg0 @ 0XE0001000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STPBRK</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STTBRK</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RSTTO</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXDIS</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXEN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >RXDIS</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RXEN</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >TXRES</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >RXRES</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>Control_reg0 @ 0XE0001000</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>17</b></td></tr></table> -</li> -<li><p>Register : mode_reg0 @ 0XE0001004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IRMODE</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >UCLKEN</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CHMODE</td><td class="hex">9:8</td><td class="hex">300</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NBSTOP</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PAR</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">4</td><td class="hex">20</td></tr> -<tr><td >CHRL</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLKS</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>mode_reg0 @ 0XE0001004</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_divider_reg0 @ 0XE0000034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >BDIV</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td><b>Baud_rate_divider_reg0 @ 0XE0000034</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>6</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_gen_reg0 @ 0XE0000018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CD</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">3e</td><td class="hex">3e</td></tr> -<tr><td><b>Baud_rate_gen_reg0 @ 0XE0000018</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : Control_reg0 @ 0XE0000000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STPBRK</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STTBRK</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RSTTO</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXDIS</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXEN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >RXDIS</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RXEN</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >TXRES</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >RXRES</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>Control_reg0 @ 0XE0000000</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>17</b></td></tr></table> -</li> -<li><p>Register : mode_reg0 @ 0XE0000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IRMODE</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >UCLKEN</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CHMODE</td><td class="hex">9:8</td><td class="hex">300</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NBSTOP</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PAR</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">4</td><td class="hex">20</td></tr> -<tr><td >CHRL</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLKS</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>mode_reg0 @ 0XE0000004</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -</ul> -<h2>PL POWER ON RESET REGISTERS</h2> -<ul> -<p>PL POWER ON RESET REGISTERS</p> -<li><p>Register : CTRL @ 0XF8007000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PCFG_POR_CNT_4K</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CTRL @ 0XF8007000</td><td></td><td class="hex"><b>20000000</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>SMC TIMING CALCULATION REGISTER UPDATE</h2> -<ul> -<p>SMC TIMING CALCULATION REGISTER UPDATE</p> -<h2>NAND SET CYCLE</h2> -<ul> -<p>NAND SET CYCLE</p> -</ul> -<h2>OPMODE</h2> -<ul> -<p>OPMODE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>SRAM/NOR CS0 SET CYCLE</h2> -<ul> -<p>SRAM/NOR CS0 SET CYCLE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>NOR CS0 BASE ADDRESS</h2> -<ul> -<p>NOR CS0 BASE ADDRESS</p> -</ul> -<h2>SRAM/NOR CS1 SET CYCLE</h2> -<ul> -<p>SRAM/NOR CS1 SET CYCLE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>NOR CS1 BASE ADDRESS</h2> -<ul> -<p>NOR CS1 BASE ADDRESS</p> -</ul> -<h2>USB RESET</h2> -<ul> -<p>USB RESET</p> -<h2>DIR MODE BANK 0</h2> -<ul> -<p>DIR MODE BANK 0</p> -</ul> -<h2>DIR MODE BANK 1</h2> -<ul> -<p>DIR MODE BANK 1</p> -<li><p>Register : DIRM_1 @ 0XE000A244</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DIRECTION_1</td><td class="hex">21:0</td><td class="hex">3fffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>DIRM_1 @ 0XE000A244</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE BANK 0</h2> -<ul> -<p>OUTPUT ENABLE BANK 0</p> -</ul> -<h2>OUTPUT ENABLE BANK 1</h2> -<ul> -<p>OUTPUT ENABLE BANK 1</p> -<li><p>Register : OEN_1 @ 0XE000A248</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >OP_ENABLE_1</td><td class="hex">21:0</td><td class="hex">3fffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>OEN_1 @ 0XE000A248</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff0000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -<h2>ENET RESET</h2> -<ul> -<p>ENET RESET</p> -<h2>DIR MODE BANK 0</h2> -<ul> -<p>DIR MODE BANK 0</p> -</ul> -<h2>DIR MODE BANK 1</h2> -<ul> -<p>DIR MODE BANK 1</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE BANK 0</h2> -<ul> -<p>OUTPUT ENABLE BANK 0</p> -</ul> -<h2>OUTPUT ENABLE BANK 1</h2> -<ul> -<p>OUTPUT ENABLE BANK 1</p> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -<h2>I2C RESET</h2> -<ul> -<p>I2C RESET</p> -<h2>DIR MODE GPIO BANK0</h2> -<ul> -<p>DIR MODE GPIO BANK0</p> -</ul> -<h2>DIR MODE GPIO BANK1</h2> -<ul> -<p>DIR MODE GPIO BANK1</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE</h2> -<ul> -<p>OUTPUT ENABLE</p> -</ul> -<h2>OUTPUT ENABLE</h2> -<ul> -<p>OUTPUT ENABLE</p> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -</ul> -</ul> -<hr/> -<h1><a name="ps7_post_config_1_0">ps7_post_config_1_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>ENABLING LEVEL SHIFTER</h2> -<ul> -<p>ENABLING LEVEL SHIFTER</p> -<li><p>Register : LVL_SHFTR_EN @ 0XF8000900</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >USER_INP_ICT_EN_0</td><td class="hex">1:0</td><td class="hex">3</td><td class="hex">3</td><td class="hex">3</td></tr> -<tr><td >USER_INP_ICT_EN_1</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">3</td><td class="hex">c</td></tr> -<tr><td><b>LVL_SHFTR_EN @ 0XF8000900</td><td></td><td class="hex"><b>f</b></td><td></td><td class="hex"><b>f</b></td></tr></table> -</li> -</ul> -<h2>FPGA RESETS TO 1</h2> -<ul> -<p>FPGA RESETS TO 1</p> -<li><p>Register : FPGA_RST_CTRL @ 0XF8000240</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reserved_3</td><td class="hex">31:25</td><td class="hex">fe000000</td><td class="hex">7f</td><td class="hex">fe000000</td></tr> -<tr><td >FPGA_ACP_RST</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td >FPGA_AXDS3_RST</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">1</td><td class="hex">800000</td></tr> -<tr><td >FPGA_AXDS2_RST</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">1</td><td class="hex">400000</td></tr> -<tr><td >FPGA_AXDS1_RST</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >FPGA_AXDS0_RST</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td >reserved_2</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">3</td><td class="hex">c0000</td></tr> -<tr><td >FSSW1_FPGA_RST</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">1</td><td class="hex">20000</td></tr> -<tr><td >FSSW0_FPGA_RST</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reserved_1</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">3</td><td class="hex">c000</td></tr> -<tr><td >FPGA_FMSW1_RST</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td >FPGA_FMSW0_RST</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >FPGA_DMA3_RST</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">1</td><td class="hex">800</td></tr> -<tr><td >FPGA_DMA2_RST</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">1</td><td class="hex">400</td></tr> -<tr><td >FPGA_DMA1_RST</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >FPGA_DMA0_RST</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >reserved</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">f</td><td class="hex">f0</td></tr> -<tr><td >FPGA3_OUT_RST</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >FPGA2_OUT_RST</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >FPGA1_OUT_RST</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >FPGA0_OUT_RST</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>FPGA_RST_CTRL @ 0XF8000240</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>ffffffff</b></td></tr></table> -</li> -</ul> -<h2>FPGA RESETS TO 0</h2> -<ul> -<p>FPGA RESETS TO 0</p> -<li><p>Register : FPGA_RST_CTRL @ 0XF8000240</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reserved_3</td><td class="hex">31:25</td><td class="hex">fe000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_ACP_RST</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS3_RST</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS2_RST</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS1_RST</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS0_RST</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_2</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FSSW1_FPGA_RST</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FSSW0_FPGA_RST</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_1</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_FMSW1_RST</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_FMSW0_RST</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA3_RST</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA2_RST</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA1_RST</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA0_RST</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA3_OUT_RST</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA2_OUT_RST</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA1_OUT_RST</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA0_OUT_RST</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>FPGA_RST_CTRL @ 0XF8000240</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>AFI REGISTERS</h2> -<ul> -<p>AFI REGISTERS</p> -<h2>AFI0 REGISTERS</h2> -<ul> -<p>AFI0 REGISTERS</p> -</ul> -<h2>AFI1 REGISTERS</h2> -<ul> -<p>AFI1 REGISTERS</p> -</ul> -<h2>AFI2 REGISTERS</h2> -<ul> -<p>AFI2 REGISTERS</p> -</ul> -<h2>AFI3 REGISTERS</h2> -<ul> -<p>AFI3 REGISTERS</p> -</ul> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -</body> -</html> -<!DOCTYPE html> -<html lang="en"> -<head> -<meta http-equiv="content-type" content="text/html;charset=UTF-8"/> -<title>Zynq PS configuration detail</title> -<style type="text/css"> -.hex {font-family:monospace ; text-align : right} -td { min-width : 80px ; } -</style> -</head> -<body> -<p style="height: 7px">Following peripherals are selected in the design. </p> -<p><br /></p> -<h2><a name="Top">Peripheral Selected</a></h2> -<ul> -<li>Quad SPI Flash</li> -<li>Enet 0</li> -<li>USB 0</li> -<li>SD 0</li> -<li>UART 0</li> -<li>UART 1</li> -<li>I2C 0</li> -<li>I2C 1</li> -<li>GPIO</li> -</ul> -<p>To see detailed information please follow below links:</p> -<ul> -<li><a href="#MIOConfTab">MIO Configuration Table</a></li> -<li><a href="#ZynqPerTab">Zynq Peripheral Configuration</a></li> -<li><a href="#DDRInfoTab">DDR Configuration Information</a></li> -<li>SLCR settings</li> -<ul> -<li><a href="#ps7_pll_init_data">PLL Init Data</a></li> -<li><a href="#ps7_clock_init_data">Clock Init Data</a></li> -<li><a href="#ps7_ddr_init_data">DDR Init Data</a></li> -<li><a href="#ps7_mio_init_data">MIO Init Data</a></li> -</ul> -</ul> -<h2><a name="MIOConfTab">MIO configuration Table</a></h2> -<ul><table border="1"> -<thead><tr> <th>MIO Pin</th> <th>Peripheral</th> <th>Signal</th> <th>IO type</th> <th>Speed</th> <th>Pullup</th> <th>Direction</th> </tr></thead> -<tr bgcolor="#FA4A46"><td><a name="MIO 0">MIO 0</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[0]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 1">MIO 1</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_ss_b</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 2">MIO 2</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[0]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 3">MIO 3</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[1]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 4">MIO 4</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[2]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 5">MIO 5</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[3]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 6">MIO 6</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_sclk</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 7">MIO 7</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[7]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 8">MIO 8</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi_fbclk</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 9">MIO 9</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[9]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 10">MIO 10</a></td><td><a href="#I2C 0">I2C 0</a></td><td>scl</td><td>LVCMOS 3.3V</td><td>slow</td><td>enabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 11">MIO 11</a></td><td><a href="#I2C 0">I2C 0</a></td><td>sda</td><td>LVCMOS 3.3V</td><td>slow</td><td>enabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 12">MIO 12</a></td><td><a href="#I2C 1">I2C 1</a></td><td>scl</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 13">MIO 13</a></td><td><a href="#I2C 1">I2C 1</a></td><td>sda</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 14">MIO 14</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[14]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 15">MIO 15</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[15]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 16">MIO 16</a></td><td><a href="#Enet 0">Enet 0</a></td><td>tx_clk</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 17">MIO 17</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[0]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 18">MIO 18</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[1]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 19">MIO 19</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[2]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 20">MIO 20</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[3]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 21">MIO 21</a></td><td><a href="#Enet 0">Enet 0</a></td><td>tx_ctl</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 22">MIO 22</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rx_clk</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 23">MIO 23</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[0]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 24">MIO 24</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[1]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 25">MIO 25</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[2]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 26">MIO 26</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[3]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 27">MIO 27</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rx_ctl</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 28">MIO 28</a></td><td><a href="#USB 0">USB 0</a></td><td>data[4]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 29">MIO 29</a></td><td><a href="#USB 0">USB 0</a></td><td>dir</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 30">MIO 30</a></td><td><a href="#USB 0">USB 0</a></td><td>stp</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 31">MIO 31</a></td><td><a href="#USB 0">USB 0</a></td><td>nxt</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 32">MIO 32</a></td><td><a href="#USB 0">USB 0</a></td><td>data[0]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 33">MIO 33</a></td><td><a href="#USB 0">USB 0</a></td><td>data[1]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 34">MIO 34</a></td><td><a href="#USB 0">USB 0</a></td><td>data[2]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 35">MIO 35</a></td><td><a href="#USB 0">USB 0</a></td><td>data[3]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 36">MIO 36</a></td><td><a href="#USB 0">USB 0</a></td><td>clk</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 37">MIO 37</a></td><td><a href="#USB 0">USB 0</a></td><td>data[5]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 38">MIO 38</a></td><td><a href="#USB 0">USB 0</a></td><td>data[6]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 39">MIO 39</a></td><td><a href="#USB 0">USB 0</a></td><td>data[7]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 40">MIO 40</a></td><td><a href="#SD 0">SD 0</a></td><td>clk</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 41">MIO 41</a></td><td><a href="#SD 0">SD 0</a></td><td>cmd</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 42">MIO 42</a></td><td><a href="#SD 0">SD 0</a></td><td>data[0]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 43">MIO 43</a></td><td><a href="#SD 0">SD 0</a></td><td>data[1]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 44">MIO 44</a></td><td><a href="#SD 0">SD 0</a></td><td>data[2]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 45">MIO 45</a></td><td><a href="#SD 0">SD 0</a></td><td>data[3]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 46">MIO 46</a></td><td><a href="#USB 0">USB 0</a></td><td>reset</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 47">MIO 47</a></td><td><a href="#SD 0">SD 0</a></td><td>cd</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#6495ED"><td><a name="MIO 48">MIO 48</a></td><td><a href="#UART 1">UART 1</a></td><td>tx</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#6495ED"><td><a name="MIO 49">MIO 49</a></td><td><a href="#UART 1">UART 1</a></td><td>rx</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 50">MIO 50</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[50]</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 51">MIO 51</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[51]</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 52">MIO 52</a></td><td><a href="#Enet 0">Enet 0</a></td><td>mdc</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 53">MIO 53</a></td><td><a href="#Enet 0">Enet 0</a></td><td>mdio</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h2><a name="ZynqPerTab">Zynq Peripheral Configuration</a></h2> -<ul><table border="1"> -<tr><thead> <th>Peripheral</th> <th>Signal Group</th> <th>Signal</th> <th>MIO</th> </thead></tr> -<tr bgcolor="#FAEBD7"><td><a name="Quad SPI Flash" >Quad SPI Flash</a></td> <td></td><td></td><td>MIO 1 .. 6</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Dual Quad SPI (4 bit) </td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Dual Quad SPI (Parallel 8 bit)</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Feedback Clk</td><td></td><td>MIO 8</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="nor" >SRAM/NOR Flash</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FFE4C4"><td><a name="nand" >NAND Flash</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DEB887"><td><a name="Enet 0" >Enet 0</a></td> <td></td><td></td><td>MIO 16 .. 27</td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>tx_clk</td><td><a href="#MIO 16">MIO 16</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[3]</td><td><a href="#MIO 20">MIO 20</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[2]</td><td><a href="#MIO 19">MIO 19</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[1]</td><td><a href="#MIO 18">MIO 18</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[0]</td><td><a href="#MIO 17">MIO 17</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>tx_ctl</td><td><a href="#MIO 21">MIO 21</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rx_clk</td><td><a href="#MIO 22">MIO 22</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[3]</td><td><a href="#MIO 26">MIO 26</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[2]</td><td><a href="#MIO 25">MIO 25</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[1]</td><td><a href="#MIO 24">MIO 24</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[0]</td><td><a href="#MIO 23">MIO 23</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rx_ctl</td><td><a href="#MIO 27">MIO 27</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td>MDIO</td><td></td><td>MIO 52 .. 53</td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>mdc</td><td><a href="#MIO 52">MIO 52</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>mdio</td><td><a href="#MIO 53">MIO 53</a></td></tr> -<tr bgcolor="#DEB887"><td><a name="enet1" >Enet 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#7FFF00"><td><a name="USB 0" >USB 0</a></td> <td></td><td></td><td>MIO 28 .. 39</td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>clk</td><td><a href="#MIO 36">MIO 36</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>dir</td><td><a href="#MIO 29">MIO 29</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>stp</td><td><a href="#MIO 30">MIO 30</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>nxt</td><td><a href="#MIO 31">MIO 31</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[0]</td><td><a href="#MIO 32">MIO 32</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[1]</td><td><a href="#MIO 33">MIO 33</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[2]</td><td><a href="#MIO 34">MIO 34</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[3]</td><td><a href="#MIO 35">MIO 35</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[4]</td><td><a href="#MIO 28">MIO 28</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[5]</td><td><a href="#MIO 37">MIO 37</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[6]</td><td><a href="#MIO 38">MIO 38</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[7]</td><td><a href="#MIO 39">MIO 39</a></td></tr> -<tr bgcolor="#7FFF00"><td><a name="usb1" >USB 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#D2691E"><td><a name="SD 0" >SD 0</a></td> <td></td><td></td><td>MIO 40 .. 45</td></tr> -<tr bgcolor="#D2691E"><td></td><td>CD</td><td></td><td>MIO 47</td></tr> -<tr bgcolor="#D2691E"><td></td><td>WP</td><td></td><td>EMIO</td></tr> -<tr bgcolor="#D2691E"><td></td><td>Power</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#D2691E"><td><a name="sd1" >SD 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#6495ED"><td><a name="UART 0" >UART 0</a></td> <td></td><td></td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>rx</td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>tx</td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td>Modem signals</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#6495ED"><td><a name="UART 1" >UART 1</a></td> <td></td><td></td><td>MIO 48 .. 49</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>rx</td><td><a href="#MIO 49">MIO 49</a></td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>tx</td><td><a href="#MIO 48">MIO 48</a></td></tr> -<tr bgcolor="#6495ED"><td></td><td>Modem Signals</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BDB76B"><td><a name="I2C 0" >I2C 0</a></td> <td></td><td></td><td>MIO 10 .. 11</td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>scl</td><td><a href="#MIO 10">MIO 10</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>sda</td><td><a href="#MIO 11">MIO 11</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td>Interrupt</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BDB76B"><td><a name="I2C 1" >I2C 1</a></td> <td></td><td></td><td>MIO 12 .. 13</td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>scl</td><td><a href="#MIO 12">MIO 12</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>sda</td><td><a href="#MIO 13">MIO 13</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td>Interrupt</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#8DBC8F"><td><a name="spi0" >SPI 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#8DBC8F"><td><a name="spi1" >SPI 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DAA520"><td><a name="can0" >CAN 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DAA520"><td><a name="can1" >CAN 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#ADD8E6"><td><a name="trace" >Trace</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BC8F8F"><td><a name="ttc0" >Timer 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BC8F8F"><td><a name="ttc1" >Timer 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FF6347"><td><a name="wdt" >Watchdog</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#EE82EE"><td><a name="pjtag" >PJTAG</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FA4A46"><td><a name="GPIO" >GPIO</a></td> <td></td><td></td><td>MIO</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="mode" >Mode</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="vcfg" >VCfg</a></td> <td></td><td></td><td>Disabled</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h2><a name="DDRInfoTab">DDR Memory information</a></h2> -<h3><a name="DDRInfoTab">DDR Controller Configuration</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="Enable DDR">Enable DDR</a></td><td>1</td></tr> -<tr> <td><a name="Memory Type">Memory Type</a></td><td>DDR 3</td></tr> -<tr> <td><a name="Memory Part">Memory Part</a></td><td>MT41K128M16 JT-125</td></tr> -<tr> <td><a name="DRAM bus width">DRAM bus width</a></td><td>32 Bit</td></tr> -<tr> <td><a name="ECC">ECC</a></td><td>Disabled</td></tr> -<tr> <td><a name="BURST Length (lppdr only)">BURST Length (lppdr only)</a></td><td>8</td></tr> -<tr> <td><a name="Internal Vref">Internal Vref</a></td><td>0</td></tr> -<tr> <td><a name="Operating Frequency (MHz)">Operating Frequency (MHz)</a></td><td>525.000000</td></tr> -<tr> <td><a name="HIGH temperature">HIGH temperature</a></td><td>Normal (0-85)</td></tr> -</table></ul> -<h3><a name="DDRInfoTab">Memory Part Configuration</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="DRAM IC bus width">DRAM IC bus width</a></td><td>16 Bits</td></tr> -<tr> <td><a name="DRAM Device Capacity">DRAM Device Capacity</a></td><td>2048 MBits</td></tr> -<tr> <td><a name="Speed Bin">Speed Bin</a></td><td>DDR3_1066F</td></tr> -<tr> <td><a name="BANK Address Count">BANK Address Count</a></td><td>3</td></tr> -<tr> <td><a name="ROW Address Count">ROW Address Count</a></td><td>14</td></tr> -<tr> <td><a name="COLUMN Address Count">COLUMN Address Count</a></td><td>10</td></tr> -<tr> <td><a name="CAS Latency">CAS Latency</a></td><td>7</td></tr> -<tr> <td><a name="CAS Write Latency">CAS Write Latency</a></td><td>6</td></tr> -<tr> <td><a name="RAS to CAS Delay">RAS to CAS Delay</a></td><td>7</td></tr> -<tr> <td><a name="RECHARGE Time">RECHARGE Time</a></td><td>7</td></tr> -<tr> <td><a name="tRC (ns )">tRC (ns )</a></td><td>48.75</td></tr> -<tr> <td><a name="tRASmin ( ns )">tRASmin ( ns )</a></td><td>35.0</td></tr> -<tr> <td><a name="tFAW">tFAW</a></td><td>40.0</td></tr> -<tr> <td><a name="ADDITIVE Latency">ADDITIVE Latency</a></td><td>0</td></tr> -</table></ul> -<h3><a name="DDRInfoTab">Training/Board Details</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="Write levelling">Write levelling</a></td><td>1</td></tr> -<tr> <td><a name="Read gate">Read gate</a></td><td>1</td></tr> -<tr> <td><a name="Read data eye">Read data eye</a></td><td>1</td></tr> -<tr> <td><a name="DQS to Clock delay [0] (ns)">DQS to Clock delay [0] (ns)</a></td><td>-0.073</td></tr> -<tr> <td><a name="DQS to Clock delay [1] (ns)">DQS to Clock delay [1] (ns)</a></td><td>-0.034</td></tr> -<tr> <td><a name="DQS to Clock delay [2] (ns)">DQS to Clock delay [2] (ns)</a></td><td>-0.03</td></tr> -<tr> <td><a name="DQS to Clock delay [3] (ns)">DQS to Clock delay [3] (ns)</a></td><td>-0.082</td></tr> -<tr> <td><a name="Board delay [0] (ns)">Board delay [0] (ns)</a></td><td>0.176</td></tr> -<tr> <td><a name="Board delay [1] (ns)">Board delay [1] (ns)</a></td><td>0.159</td></tr> -<tr> <td><a name="Board delay [2] (ns)">Board delay [2] (ns)</a></td><td>0.162</td></tr> -<tr> <td><a name="Board delay [3] (ns)">Board delay [3] (ns)</a></td><td>0.187</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h1><a name="ps7_pll_init_data_2_0">ps7_pll_init_data_2_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>PLL SLCR REGISTERS</h2> -<ul> -<p>PLL SLCR REGISTERS</p> -<h2>ARM PLL INIT</h2> -<ul> -<p>ARM PLL INIT</p> -<li><p>Register : ARM_PLL_CFG @ 0XF8000110</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">177</td><td class="hex">177000</td></tr> -<tr><td><b>ARM_PLL_CFG @ 0XF8000110</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1772c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">1a</td><td class="hex">1a000</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>1a000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >ARM_PLL_LOCK</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<li><p>Register : ARM_CLK_CTRL @ 0XF8000120</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >CPU_6OR4XCLKACT</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td >CPU_3OR2XCLKACT</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">1</td><td class="hex">2000000</td></tr> -<tr><td >CPU_2XCLKACT</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">1</td><td class="hex">4000000</td></tr> -<tr><td >CPU_1XCLKACT</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">1</td><td class="hex">8000000</td></tr> -<tr><td >CPU_PERI_CLKACT</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td><b>ARM_CLK_CTRL @ 0XF8000120</td><td></td><td class="hex"><b>1f003f30</b></td><td></td><td class="hex"><b>1f000200</b></td></tr></table> -</li> -</ul> -<h2>DDR PLL INIT</h2> -<ul> -<p>DDR PLL INIT</p> -<li><p>Register : DDR_PLL_CFG @ 0XF8000114</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">1db</td><td class="hex">1db000</td></tr> -<tr><td><b>DDR_PLL_CFG @ 0XF8000114</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1db2c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">15</td><td class="hex">15000</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>15000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DDR_PLL_LOCK</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>2</b></td><td></td><td class="hex"><b>2</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<li><p>Register : DDR_CLK_CTRL @ 0XF8000124</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DDR_3XCLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >DDR_2XCLKACT</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DDR_3XCLK_DIVISOR</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td >DDR_2XCLK_DIVISOR</td><td class="hex">31:26</td><td class="hex">fc000000</td><td class="hex">3</td><td class="hex">c000000</td></tr> -<tr><td><b>DDR_CLK_CTRL @ 0XF8000124</td><td></td><td class="hex"><b>fff00003</b></td><td></td><td class="hex"><b>c200003</b></td></tr></table> -</li> -</ul> -<h2>IO PLL INIT</h2> -<ul> -<p>IO PLL INIT</p> -<li><p>Register : IO_PLL_CFG @ 0XF8000118</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">1f4</td><td class="hex">1f4000</td></tr> -<tr><td><b>IO_PLL_CFG @ 0XF8000118</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1f42c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">14</td><td class="hex">14000</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>14000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IO_PLL_LOCK</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>4</b></td><td></td><td class="hex"><b>4</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -</ul> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_clock_init_data_2_0">ps7_clock_init_data_2_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>CLOCK CONTROL SLCR REGISTERS</h2> -<ul> -<p>CLOCK CONTROL SLCR REGISTERS</p> -<li><p>Register : DCI_CLK_CTRL @ 0XF8000128</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">34</td><td class="hex">3400</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td><b>DCI_CLK_CTRL @ 0XF8000128</td><td></td><td class="hex"><b>3f03f01</b></td><td></td><td class="hex"><b>203401</b></td></tr></table> -</li> -<li><p>Register : GEM0_RCLK_CTRL @ 0XF8000138</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>GEM0_RCLK_CTRL @ 0XF8000138</td><td></td><td class="hex"><b>11</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -<li><p>Register : GEM0_CLK_CTRL @ 0XF8000140</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">8</td><td class="hex">800</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>GEM0_CLK_CTRL @ 0XF8000140</td><td></td><td class="hex"><b>3f03f71</b></td><td></td><td class="hex"><b>100801</b></td></tr></table> -</li> -<li><p>Register : LQSPI_CLK_CTRL @ 0XF800014C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">5</td><td class="hex">500</td></tr> -<tr><td><b>LQSPI_CLK_CTRL @ 0XF800014C</td><td></td><td class="hex"><b>3f31</b></td><td></td><td class="hex"><b>501</b></td></tr></table> -</li> -<li><p>Register : SDIO_CLK_CTRL @ 0XF8000150</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT0</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >CLKACT1</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">14</td><td class="hex">1400</td></tr> -<tr><td><b>SDIO_CLK_CTRL @ 0XF8000150</td><td></td><td class="hex"><b>3f33</b></td><td></td><td class="hex"><b>1401</b></td></tr></table> -</li> -<li><p>Register : UART_CLK_CTRL @ 0XF8000154</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT0</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >CLKACT1</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">14</td><td class="hex">1400</td></tr> -<tr><td><b>UART_CLK_CTRL @ 0XF8000154</td><td></td><td class="hex"><b>3f33</b></td><td></td><td class="hex"><b>1403</b></td></tr></table> -</li> -<li><p>Register : PCAP_CLK_CTRL @ 0XF8000168</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">5</td><td class="hex">500</td></tr> -<tr><td><b>PCAP_CLK_CTRL @ 0XF8000168</td><td></td><td class="hex"><b>3f31</b></td><td></td><td class="hex"><b>501</b></td></tr></table> -</li> -<li><p>Register : FPGA0_CLK_CTRL @ 0XF8000170</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">a</td><td class="hex">a00</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA0_CLK_CTRL @ 0XF8000170</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100a00</b></td></tr></table> -</li> -<li><p>Register : FPGA1_CLK_CTRL @ 0XF8000180</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">3</td><td class="hex">30</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">6</td><td class="hex">600</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA1_CLK_CTRL @ 0XF8000180</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100630</b></td></tr></table> -</li> -<li><p>Register : FPGA2_CLK_CTRL @ 0XF8000190</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">2</td><td class="hex">20</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">35</td><td class="hex">3500</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td><b>FPGA2_CLK_CTRL @ 0XF8000190</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>203520</b></td></tr></table> -</li> -<li><p>Register : FPGA3_CLK_CTRL @ 0XF80001A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">a</td><td class="hex">a00</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA3_CLK_CTRL @ 0XF80001A0</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100a00</b></td></tr></table> -</li> -<li><p>Register : CLK_621_TRUE @ 0XF80001C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLK_621_TRUE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>CLK_621_TRUE @ 0XF80001C4</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -<li><p>Register : APER_CLK_CTRL @ 0XF800012C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DMA_CPU_2XCLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >USB0_CPU_1XCLKACT</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >USB1_CPU_1XCLKACT</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >GEM0_CPU_1XCLKACT</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">1</td><td class="hex">40</td></tr> -<tr><td >GEM1_CPU_1XCLKACT</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SDI0_CPU_1XCLKACT</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">1</td><td class="hex">400</td></tr> -<tr><td >SDI1_CPU_1XCLKACT</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SPI0_CPU_1XCLKACT</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SPI1_CPU_1XCLKACT</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CAN0_CPU_1XCLKACT</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CAN1_CPU_1XCLKACT</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >I2C0_CPU_1XCLKACT</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">1</td><td class="hex">40000</td></tr> -<tr><td >I2C1_CPU_1XCLKACT</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td >UART0_CPU_1XCLKACT</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td >UART1_CPU_1XCLKACT</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >GPIO_CPU_1XCLKACT</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">1</td><td class="hex">400000</td></tr> -<tr><td >LQSPI_CPU_1XCLKACT</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">1</td><td class="hex">800000</td></tr> -<tr><td >SMC_CPU_1XCLKACT</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td><b>APER_CLK_CTRL @ 0XF800012C</td><td></td><td class="hex"><b>1ffcccd</b></td><td></td><td class="hex"><b>1fc044d</b></td></tr></table> -</li> -</ul> -<h2>THIS SHOULD BE BLANK</h2> -<ul> -<p>THIS SHOULD BE BLANK</p> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_ddr_init_data_2_0">ps7_ddr_init_data_2_0</a></h1> -<ul> -<h2>DDR INITIALIZATION</h2> -<ul> -<p>DDR INITIALIZATION</p> -<h2>LOCK DDR</h2> -<ul> -<p>LOCK DDR</p> -<li><p>Register : ddrc_ctrl @ 0XF8006000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_soft_rstb</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_powerdown_en</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_data_bus_width</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_burst8_refresh</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rdwr_idle_gap</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_ddrc_dis_rd_bypass</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_act_bypass</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_auto_refresh</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ddrc_ctrl @ 0XF8006000</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>80</b></td></tr></table> -</li> -</ul> -<li><p>Register : Two_rank_cfg @ 0XF8006004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_rfc_nom_x32</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">7f</td><td class="hex">7f</td></tr> -<tr><td >reg_ddrc_active_ranks</td><td class="hex">13:12</td><td class="hex">3000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >reg_ddrc_addrmap_cs_bit0</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_wr_odt_block</td><td class="hex">20:19</td><td class="hex">180000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td >reg_ddrc_diff_rank_rd_2cycle_gap</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_cs_bit1</td><td class="hex">26:22</td><td class="hex">7c00000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_open_bank</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_4bank_ram</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>Two_rank_cfg @ 0XF8006004</td><td></td><td class="hex"><b>1fffffff</b></td><td></td><td class="hex"><b>8107f</b></td></tr></table> -</li> -<li><p>Register : HPR_reg @ 0XF8006008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_hpr_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">f</td><td class="hex">f</td></tr> -<tr><td >reg_ddrc_hpr_max_starve_x32</td><td class="hex">21:11</td><td class="hex">3ff800</td><td class="hex">f</td><td class="hex">7800</td></tr> -<tr><td >reg_ddrc_hpr_xact_run_length</td><td class="hex">25:22</td><td class="hex">3c00000</td><td class="hex">f</td><td class="hex">3c00000</td></tr> -<tr><td><b>HPR_reg @ 0XF8006008</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>3c0780f</b></td></tr></table> -</li> -<li><p>Register : LPR_reg @ 0XF800600C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_lpr_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_lpr_max_starve_x32</td><td class="hex">21:11</td><td class="hex">3ff800</td><td class="hex">2</td><td class="hex">1000</td></tr> -<tr><td >reg_ddrc_lpr_xact_run_length</td><td class="hex">25:22</td><td class="hex">3c00000</td><td class="hex">8</td><td class="hex">2000000</td></tr> -<tr><td><b>LPR_reg @ 0XF800600C</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>2001001</b></td></tr></table> -</li> -<li><p>Register : WR_reg @ 0XF8006010</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_w_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_w_xact_run_length</td><td class="hex">14:11</td><td class="hex">7800</td><td class="hex">8</td><td class="hex">4000</td></tr> -<tr><td >reg_ddrc_w_max_starve_x32</td><td class="hex">25:15</td><td class="hex">3ff8000</td><td class="hex">2</td><td class="hex">10000</td></tr> -<tr><td><b>WR_reg @ 0XF8006010</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>14001</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg0 @ 0XF8006014</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_rc</td><td class="hex">5:0</td><td class="hex">3f</td><td class="hex">1a</td><td class="hex">1a</td></tr> -<tr><td >reg_ddrc_t_rfc_min</td><td class="hex">13:6</td><td class="hex">3fc0</td><td class="hex">54</td><td class="hex">1500</td></tr> -<tr><td >reg_ddrc_post_selfref_gap_x32</td><td class="hex">20:14</td><td class="hex">1fc000</td><td class="hex">10</td><td class="hex">40000</td></tr> -<tr><td><b>DRAM_param_reg0 @ 0XF8006014</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>4151a</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg1 @ 0XF8006018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_wr2pre</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">12</td><td class="hex">12</td></tr> -<tr><td >reg_ddrc_powerdown_to_x32</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">6</td><td class="hex">c0</td></tr> -<tr><td >reg_ddrc_t_faw</td><td class="hex">15:10</td><td class="hex">fc00</td><td class="hex">15</td><td class="hex">5400</td></tr> -<tr><td >reg_ddrc_t_ras_max</td><td class="hex">21:16</td><td class="hex">3f0000</td><td class="hex">23</td><td class="hex">230000</td></tr> -<tr><td >reg_ddrc_t_ras_min</td><td class="hex">26:22</td><td class="hex">7c00000</td><td class="hex">13</td><td class="hex">4c00000</td></tr> -<tr><td >reg_ddrc_t_cke</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">4</td><td class="hex">40000000</td></tr> -<tr><td><b>DRAM_param_reg1 @ 0XF8006018</td><td></td><td class="hex"><b>f7ffffff</b></td><td></td><td class="hex"><b>44e354d2</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg2 @ 0XF800601C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_write_latency</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">5</td><td class="hex">5</td></tr> -<tr><td >reg_ddrc_rd2wr</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >reg_ddrc_wr2rd</td><td class="hex">14:10</td><td class="hex">7c00</td><td class="hex">e</td><td class="hex">3800</td></tr> -<tr><td >reg_ddrc_t_xp</td><td class="hex">19:15</td><td class="hex">f8000</td><td class="hex">4</td><td class="hex">20000</td></tr> -<tr><td >reg_ddrc_pad_pd</td><td class="hex">22:20</td><td class="hex">700000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rd2pre</td><td class="hex">27:23</td><td class="hex">f800000</td><td class="hex">4</td><td class="hex">2000000</td></tr> -<tr><td >reg_ddrc_t_rcd</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">7</td><td class="hex">70000000</td></tr> -<tr><td><b>DRAM_param_reg2 @ 0XF800601C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>720238e5</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg3 @ 0XF8006020</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_ccd</td><td class="hex">4:2</td><td class="hex">1c</td><td class="hex">4</td><td class="hex">10</td></tr> -<tr><td >reg_ddrc_t_rrd</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">6</td><td class="hex">c0</td></tr> -<tr><td >reg_ddrc_refresh_margin</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >reg_ddrc_t_rp</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">7</td><td class="hex">7000</td></tr> -<tr><td >reg_ddrc_refresh_to_x32</td><td class="hex">20:16</td><td class="hex">1f0000</td><td class="hex">8</td><td class="hex">80000</td></tr> -<tr><td >reg_ddrc_sdram</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >reg_ddrc_mobile</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_clock_stop_en</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_read_latency</td><td class="hex">28:24</td><td class="hex">1f000000</td><td class="hex">7</td><td class="hex">7000000</td></tr> -<tr><td >reg_phy_mode_ddr1_ddr2</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">1</td><td class="hex">20000000</td></tr> -<tr><td >reg_ddrc_dis_pad_pd</td><td class="hex">30:30</td><td class="hex">40000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_loopback</td><td class="hex">31:31</td><td class="hex">80000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_param_reg3 @ 0XF8006020</td><td></td><td class="hex"><b>fffffffc</b></td><td></td><td class="hex"><b>272872d0</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg4 @ 0XF8006024</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_en_2t_timing_mode</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_prefer_write</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_max_rank_rd</td><td class="hex">5:2</td><td class="hex">3c</td><td class="hex">f</td><td class="hex">3c</td></tr> -<tr><td >reg_ddrc_mr_wr</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_addr</td><td class="hex">8:7</td><td class="hex">180</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_data</td><td class="hex">24:9</td><td class="hex">1fffe00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ddrc_reg_mr_wr_busy</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_type</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_rdata_valid</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_param_reg4 @ 0XF8006024</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>3c</b></td></tr></table> -</li> -<li><p>Register : DRAM_init_param @ 0XF8006028</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_final_wait_x32</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">7</td><td class="hex">7</td></tr> -<tr><td >reg_ddrc_pre_ocd_x32</td><td class="hex">10:7</td><td class="hex">780</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_t_mrd</td><td class="hex">13:11</td><td class="hex">3800</td><td class="hex">4</td><td class="hex">2000</td></tr> -<tr><td><b>DRAM_init_param @ 0XF8006028</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2007</b></td></tr></table> -</li> -<li><p>Register : DRAM_EMR_reg @ 0XF800602C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_emr2</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">8</td><td class="hex">8</td></tr> -<tr><td >reg_ddrc_emr3</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_EMR_reg @ 0XF800602C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>8</b></td></tr></table> -</li> -<li><p>Register : DRAM_EMR_MR_reg @ 0XF8006030</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_mr</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">930</td><td class="hex">930</td></tr> -<tr><td >reg_ddrc_emr</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">4</td><td class="hex">40000</td></tr> -<tr><td><b>DRAM_EMR_MR_reg @ 0XF8006030</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>40930</b></td></tr></table> -</li> -<li><p>Register : DRAM_burst8_rdwr @ 0XF8006034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_burst_rdwr</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">4</td><td class="hex">4</td></tr> -<tr><td >reg_ddrc_pre_cke_x1024</td><td class="hex">13:4</td><td class="hex">3ff0</td><td class="hex">101</td><td class="hex">1010</td></tr> -<tr><td >reg_ddrc_post_cke_x1024</td><td class="hex">25:16</td><td class="hex">3ff0000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_ddrc_burstchop</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_burst8_rdwr @ 0XF8006034</td><td></td><td class="hex"><b>13ff3fff</b></td><td></td><td class="hex"><b>11014</b></td></tr></table> -</li> -<li><p>Register : DRAM_disable_DQ @ 0XF8006038</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_force_low_pri_n</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_dq</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_debug_mode</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_level_start</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_level_start</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq0_wait_t</td><td class="hex">12:9</td><td class="hex">1e00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_disable_DQ @ 0XF8006038</td><td></td><td class="hex"><b>1fc3</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_bank @ 0XF800603C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_bank_b0</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">7</td><td class="hex">7</td></tr> -<tr><td >reg_ddrc_addrmap_bank_b1</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">7</td><td class="hex">70</td></tr> -<tr><td >reg_ddrc_addrmap_bank_b2</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">7</td><td class="hex">700</td></tr> -<tr><td >reg_ddrc_addrmap_col_b5</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b6</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_addr_map_bank @ 0XF800603C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>777</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_col @ 0XF8006040</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_col_b2</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b3</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b4</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b7</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b8</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b9</td><td class="hex">23:20</td><td class="hex">f00000</td><td class="hex">f</td><td class="hex">f00000</td></tr> -<tr><td >reg_ddrc_addrmap_col_b10</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">f</td><td class="hex">f000000</td></tr> -<tr><td >reg_ddrc_addrmap_col_b11</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">f</td><td class="hex">f0000000</td></tr> -<tr><td><b>DRAM_addr_map_col @ 0XF8006040</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>fff00000</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_row @ 0XF8006044</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_row_b0</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td >reg_ddrc_addrmap_row_b1</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">6</td><td class="hex">60</td></tr> -<tr><td >reg_ddrc_addrmap_row_b2_11</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">6</td><td class="hex">600</td></tr> -<tr><td >reg_ddrc_addrmap_row_b12</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">6</td><td class="hex">6000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b13</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">6</td><td class="hex">60000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b14</td><td class="hex">23:20</td><td class="hex">f00000</td><td class="hex">f</td><td class="hex">f00000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b15</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">f</td><td class="hex">f000000</td></tr> -<tr><td><b>DRAM_addr_map_row @ 0XF8006044</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>ff66666</b></td></tr></table> -</li> -<li><p>Register : DRAM_ODT_reg @ 0XF8006048</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_rank0_rd_odt</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank0_wr_odt</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >reg_ddrc_rank1_rd_odt</td><td class="hex">8:6</td><td class="hex">1c0</td><td class="hex">1</td><td class="hex">40</td></tr> -<tr><td >reg_ddrc_rank1_wr_odt</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >reg_phy_rd_local_odt</td><td class="hex">13:12</td><td class="hex">3000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_local_odt</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">3</td><td class="hex">c000</td></tr> -<tr><td >reg_phy_idle_local_odt</td><td class="hex">17:16</td><td class="hex">30000</td><td class="hex">3</td><td class="hex">30000</td></tr> -<tr><td >reg_ddrc_rank2_rd_odt</td><td class="hex">20:18</td><td class="hex">1c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank2_wr_odt</td><td class="hex">23:21</td><td class="hex">e00000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank3_rd_odt</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rank3_wr_odt</td><td class="hex">29:27</td><td class="hex">38000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_ODT_reg @ 0XF8006048</td><td></td><td class="hex"><b>3fffffff</b></td><td></td><td class="hex"><b>3c248</b></td></tr></table> -</li> -<li><p>Register : phy_cmd_timeout_rddata_cpt @ 0XF8006050</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_cmd_to_data</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_cmd_to_data</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rdc_we_to_re_delay</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">8</td><td class="hex">800</td></tr> -<tr><td >reg_phy_rdc_fifo_rst_disable</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_use_fixed_re</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_phy_rdc_fifo_rst_err_cnt_clr</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dis_phy_ctrl_rstn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_clk_stall_level</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_num_of_dq0</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">7</td><td class="hex">7000000</td></tr> -<tr><td >reg_phy_wrlvl_num_of_dq0</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">7</td><td class="hex">70000000</td></tr> -<tr><td><b>phy_cmd_timeout_rddata_cpt @ 0XF8006050</td><td></td><td class="hex"><b>ff0f8fff</b></td><td></td><td class="hex"><b>77010800</b></td></tr></table> -</li> -<li><p>Register : DLL_calib @ 0XF8006058</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dll_calib_to_min_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_dll_calib_to_max_x1024</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >reg_ddrc_dis_dll_calib</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DLL_calib @ 0XF8006058</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>101</b></td></tr></table> -</li> -<li><p>Register : ODT_delay_hold @ 0XF800605C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_rd_odt_delay</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">3</td><td class="hex">3</td></tr> -<tr><td >reg_ddrc_wr_odt_delay</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rd_odt_hold</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_wr_odt_hold</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">5</td><td class="hex">5000</td></tr> -<tr><td><b>ODT_delay_hold @ 0XF800605C</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>5003</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg1 @ 0XF8006060</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_pageclose</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_lpr_num_entries</td><td class="hex">6:1</td><td class="hex">7e</td><td class="hex">1f</td><td class="hex">3e</td></tr> -<tr><td >reg_ddrc_auto_pre_en</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_refresh_update_level</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_wc</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_collision_page_opt</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_selfref_en</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ctrl_reg1 @ 0XF8006060</td><td></td><td class="hex"><b>17ff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg2 @ 0XF8006064</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_go2critical_hysteresis</td><td class="hex">12:5</td><td class="hex">1fe0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_go2critical_en</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">1</td><td class="hex">20000</td></tr> -<tr><td><b>ctrl_reg2 @ 0XF8006064</td><td></td><td class="hex"><b>21fe0</b></td><td></td><td class="hex"><b>20000</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg3 @ 0XF8006068</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_wrlvl_ww</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">41</td><td class="hex">41</td></tr> -<tr><td >reg_ddrc_rdlvl_rr</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">41</td><td class="hex">4100</td></tr> -<tr><td >reg_ddrc_dfi_t_wlmrd</td><td class="hex">25:16</td><td class="hex">3ff0000</td><td class="hex">28</td><td class="hex">280000</td></tr> -<tr><td><b>ctrl_reg3 @ 0XF8006068</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>284141</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg4 @ 0XF800606C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >dfi_t_ctrlupd_interval_min_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">10</td><td class="hex">10</td></tr> -<tr><td >dfi_t_ctrlupd_interval_max_x1024</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">16</td><td class="hex">1600</td></tr> -<tr><td><b>ctrl_reg4 @ 0XF800606C</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>1610</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg5 @ 0XF8006078</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dfi_t_ctrl_delay</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_dfi_t_dram_clk_disable</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >reg_ddrc_dfi_t_dram_clk_enable</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >reg_ddrc_t_cksre</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">6</td><td class="hex">6000</td></tr> -<tr><td >reg_ddrc_t_cksrx</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">6</td><td class="hex">60000</td></tr> -<tr><td >reg_ddrc_t_ckesr</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">4</td><td class="hex">400000</td></tr> -<tr><td><b>ctrl_reg5 @ 0XF8006078</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>466111</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg6 @ 0XF800607C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_ckpde</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">2</td><td class="hex">2</td></tr> -<tr><td >reg_ddrc_t_ckpdx</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">2</td><td class="hex">20</td></tr> -<tr><td >reg_ddrc_t_ckdpde</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >reg_ddrc_t_ckdpdx</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">2</td><td class="hex">2000</td></tr> -<tr><td >reg_ddrc_t_ckcsx</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">3</td><td class="hex">30000</td></tr> -<tr><td><b>ctrl_reg6 @ 0XF800607C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>32222</b></td></tr></table> -</li> -<li><p>Register : CHE_REFRESH_TIMER01 @ 0XF80060A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >refresh_timer0_start_value_x32</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >refresh_timer1_start_value_x32</td><td class="hex">23:12</td><td class="hex">fff000</td><td class="hex">8</td><td class="hex">8000</td></tr> -<tr><td><b>CHE_REFRESH_TIMER01 @ 0XF80060A0</td><td></td><td class="hex"><b>ffffff</b></td><td></td><td class="hex"><b>8000</b></td></tr></table> -</li> -<li><p>Register : CHE_T_ZQ @ 0XF80060A4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dis_auto_zq</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_ddr3</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >reg_ddrc_t_mod</td><td class="hex">11:2</td><td class="hex">ffc</td><td class="hex">200</td><td class="hex">800</td></tr> -<tr><td >reg_ddrc_t_zq_long_nop</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">200</td><td class="hex">200000</td></tr> -<tr><td >reg_ddrc_t_zq_short_nop</td><td class="hex">31:22</td><td class="hex">ffc00000</td><td class="hex">40</td><td class="hex">10000000</td></tr> -<tr><td><b>CHE_T_ZQ @ 0XF80060A4</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>10200802</b></td></tr></table> -</li> -<li><p>Register : CHE_T_ZQ_Short_Interval_Reg @ 0XF80060A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >t_zq_short_interval_x1024</td><td class="hex">19:0</td><td class="hex">fffff</td><td class="hex">c845</td><td class="hex">c845</td></tr> -<tr><td >dram_rstn_x1024</td><td class="hex">27:20</td><td class="hex">ff00000</td><td class="hex">67</td><td class="hex">6700000</td></tr> -<tr><td><b>CHE_T_ZQ_Short_Interval_Reg @ 0XF80060A8</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>670c845</b></td></tr></table> -</li> -<li><p>Register : deep_pwrdwn_reg @ 0XF80060AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >deeppowerdown_en</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >deeppowerdown_to_x1024</td><td class="hex">8:1</td><td class="hex">1fe</td><td class="hex">ff</td><td class="hex">1fe</td></tr> -<tr><td><b>deep_pwrdwn_reg @ 0XF80060AC</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>1fe</b></td></tr></table> -</li> -<li><p>Register : reg_2c @ 0XF80060B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >dfi_wrlvl_max_x1024</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">fff</td><td class="hex">fff</td></tr> -<tr><td >dfi_rdlvl_max_x1024</td><td class="hex">23:12</td><td class="hex">fff000</td><td class="hex">fff</td><td class="hex">fff000</td></tr> -<tr><td >ddrc_reg_twrlvl_max_error</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ddrc_reg_trdlvl_max_error</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dfi_wr_level_en</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">1</td><td class="hex">4000000</td></tr> -<tr><td >reg_ddrc_dfi_rd_dqs_gate_level</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">1</td><td class="hex">8000000</td></tr> -<tr><td >reg_ddrc_dfi_rd_data_eye_train</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td><b>reg_2c @ 0XF80060B0</td><td></td><td class="hex"><b>1fffffff</b></td><td></td><td class="hex"><b>1cffffff</b></td></tr></table> -</li> -<li><p>Register : reg_2d @ 0XF80060B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_2t_delay</td><td class="hex">8:0</td><td class="hex">1ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_skip_ocd</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >reg_ddrc_dis_pre_bypass</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_2d @ 0XF80060B4</td><td></td><td class="hex"><b>7ff</b></td><td></td><td class="hex"><b>200</b></td></tr></table> -</li> -<li><p>Register : dfi_timing @ 0XF80060B8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dfi_t_rddata_en</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td >reg_ddrc_dfi_t_ctrlup_min</td><td class="hex">14:5</td><td class="hex">7fe0</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >reg_ddrc_dfi_t_ctrlup_max</td><td class="hex">24:15</td><td class="hex">1ff8000</td><td class="hex">40</td><td class="hex">200000</td></tr> -<tr><td><b>dfi_timing @ 0XF80060B8</td><td></td><td class="hex"><b>1ffffff</b></td><td></td><td class="hex"><b>200066</b></td></tr></table> -</li> -<li><p>Register : CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Clear_Uncorrectable_DRAM_ECC_error</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >Clear_Correctable_DRAM_ECC_error</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td><b>CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</td><td></td><td class="hex"><b>3</b></td><td></td><td class="hex"><b>3</b></td></tr></table> -</li> -</ul> -<li><p>Register : CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Clear_Uncorrectable_DRAM_ECC_error</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Clear_Correctable_DRAM_ECC_error</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</td><td></td><td class="hex"><b>3</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_CORR_ECC_LOG_REG_OFFSET @ 0XF80060C8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CORR_ECC_LOG_VALID</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ECC_CORRECTED_BIT_NUM</td><td class="hex">7:1</td><td class="hex">fe</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_CORR_ECC_LOG_REG_OFFSET @ 0XF80060C8</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_UNCORR_ECC_LOG_REG_OFFSET @ 0XF80060DC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNCORR_ECC_LOG_VALID</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_UNCORR_ECC_LOG_REG_OFFSET @ 0XF80060DC</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_ECC_STATS_REG_OFFSET @ 0XF80060F0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STAT_NUM_CORR_ERR</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STAT_NUM_UNCORR_ERR</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_ECC_STATS_REG_OFFSET @ 0XF80060F0</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : ECC_scrub @ 0XF80060F4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_ecc_mode</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_scrub</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td><b>ECC_scrub @ 0XF80060F4</td><td></td><td class="hex"><b>f</b></td><td></td><td class="hex"><b>8</b></td></tr></table> -</li> -<li><p>Register : phy_rcvr_enable @ 0XF8006114</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_dif_on</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dif_off</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rcvr_enable @ 0XF8006114</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : PHY_Config0 @ 0XF8006118</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config0 @ 0XF8006118</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config1 @ 0XF800611C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config1 @ 0XF800611C</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config2 @ 0XF8006120</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config2 @ 0XF8006120</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config3 @ 0XF8006124</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_tx</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_board_lpbk_rx</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config3 @ 0XF8006124</td><td></td><td class="hex"><b>7fffffff</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio0 @ 0XF800612C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8f</td><td class="hex">23c00</td></tr> -<tr><td><b>phy_init_ratio0 @ 0XF800612C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>23c00</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio1 @ 0XF8006130</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8a</td><td class="hex">22800</td></tr> -<tr><td><b>phy_init_ratio1 @ 0XF8006130</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>22800</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio2 @ 0XF8006134</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8b</td><td class="hex">22c00</td></tr> -<tr><td><b>phy_init_ratio2 @ 0XF8006134</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>22c00</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio3 @ 0XF8006138</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">92</td><td class="hex">24800</td></tr> -<tr><td><b>phy_init_ratio3 @ 0XF8006138</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>24800</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg0 @ 0XF8006140</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg0 @ 0XF8006140</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg1 @ 0XF8006144</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg1 @ 0XF8006144</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg2 @ 0XF8006148</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg2 @ 0XF8006148</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg3 @ 0XF800614C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg3 @ 0XF800614C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg0 @ 0XF8006154</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">77</td><td class="hex">77</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg0 @ 0XF8006154</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>77</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg1 @ 0XF8006158</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">7c</td><td class="hex">7c</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg1 @ 0XF8006158</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>7c</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg2 @ 0XF800615C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">7c</td><td class="hex">7c</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg2 @ 0XF800615C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>7c</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg3 @ 0XF8006160</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">75</td><td class="hex">75</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg3 @ 0XF8006160</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>75</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg0 @ 0XF8006168</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e4</td><td class="hex">e4</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg0 @ 0XF8006168</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e4</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg1 @ 0XF800616C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">df</td><td class="hex">df</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg1 @ 0XF800616C</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>df</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg2 @ 0XF8006170</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e0</td><td class="hex">e0</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg2 @ 0XF8006170</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e0</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg3 @ 0XF8006174</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e7</td><td class="hex">e7</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg3 @ 0XF8006174</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e7</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv0 @ 0XF800617C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">b7</td><td class="hex">b7</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv0 @ 0XF800617C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>b7</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv1 @ 0XF8006180</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">bc</td><td class="hex">bc</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv1 @ 0XF8006180</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>bc</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv2 @ 0XF8006184</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">bc</td><td class="hex">bc</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv2 @ 0XF8006184</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>bc</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv3 @ 0XF8006188</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">b5</td><td class="hex">b5</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv3 @ 0XF8006188</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>b5</b></td></tr></table> -</li> -<li><p>Register : reg_64 @ 0XF8006190</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_loopback</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bl2</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_at_spd_atpg</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_enable</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_force_err</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_mode</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_invert_clkout</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_phy_all_dq_mpr_rd_resp</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_sel_logic</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">100</td><td class="hex">40000</td></tr> -<tr><td >reg_phy_ctrl_slave_force</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_delay</td><td class="hex">27:21</td><td class="hex">fe00000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_use_rank0_delays</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td >reg_phy_lpddr</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_cmd_latency</td><td class="hex">30:30</td><td class="hex">40000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_int_lpbk</td><td class="hex">31:31</td><td class="hex">80000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_64 @ 0XF8006190</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>10040080</b></td></tr></table> -</li> -<li><p>Register : reg_65 @ 0XF8006194</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_rl_delay</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">2</td><td class="hex">2</td></tr> -<tr><td >reg_phy_rd_rl_delay</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >reg_phy_dll_lock_diff</td><td class="hex">13:10</td><td class="hex">3c00</td><td class="hex">f</td><td class="hex">3c00</td></tr> -<tr><td >reg_phy_use_wr_level</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">1</td><td class="hex">4000</td></tr> -<tr><td >reg_phy_use_rd_dqs_gate_level</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">1</td><td class="hex">8000</td></tr> -<tr><td >reg_phy_use_rd_data_eye_level</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_phy_dis_calib_rst</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_delay</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_65 @ 0XF8006194</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>1fc82</b></td></tr></table> -</li> -<li><p>Register : page_mask @ 0XF8006204</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_page_addr_mask</td><td class="hex">31:0</td><td class="hex">ffffffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>page_mask @ 0XF8006204</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port0 @ 0XF8006208</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port0 @ 0XF8006208</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port1 @ 0XF800620C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port1 @ 0XF800620C</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port2 @ 0XF8006210</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port2 @ 0XF8006210</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port3 @ 0XF8006214</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_rmw_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>axi_priority_wr_port3 @ 0XF8006214</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>803ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port0 @ 0XF8006218</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port0 @ 0XF8006218</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port1 @ 0XF800621C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port1 @ 0XF800621C</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port2 @ 0XF8006220</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port2 @ 0XF8006220</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port3 @ 0XF8006224</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port3 @ 0XF8006224</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl0 @ 0XF80062A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_lpddr2</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_per_bank_refresh</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_derate_enable</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr4_margin</td><td class="hex">11:4</td><td class="hex">ff0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>lpddr_ctrl0 @ 0XF80062A8</td><td></td><td class="hex"><b>ff7</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl1 @ 0XF80062AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_mr4_read_interval</td><td class="hex">31:0</td><td class="hex">ffffffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>lpddr_ctrl1 @ 0XF80062AC</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl2 @ 0XF80062B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_min_stable_clock_x1</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">5</td><td class="hex">5</td></tr> -<tr><td >reg_ddrc_idle_after_reset_x32</td><td class="hex">11:4</td><td class="hex">ff0</td><td class="hex">12</td><td class="hex">120</td></tr> -<tr><td >reg_ddrc_t_mrw</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">5</td><td class="hex">5000</td></tr> -<tr><td><b>lpddr_ctrl2 @ 0XF80062B0</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>5125</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl3 @ 0XF80062B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_max_auto_init_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">a6</td><td class="hex">a6</td></tr> -<tr><td >reg_ddrc_dev_zqinit_x32</td><td class="hex">17:8</td><td class="hex">3ff00</td><td class="hex">12</td><td class="hex">1200</td></tr> -<tr><td><b>lpddr_ctrl3 @ 0XF80062B4</td><td></td><td class="hex"><b>3ffff</b></td><td></td><td class="hex"><b>12a6</b></td></tr></table> -</li> -<h2>POLL ON DCI STATUS</h2> -<ul> -<p>POLL ON DCI STATUS</p> -<li><p>Register : DDRIOB_DCI_STATUS @ 0XF8000B74</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DONE</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>DDRIOB_DCI_STATUS @ 0XF8000B74</td><td></td><td class="hex"><b>2000</b></td><td></td><td class="hex"><b>2000</b></td></tr></table> -</li> -</ul> -<h2>UNLOCK DDR</h2> -<ul> -<p>UNLOCK DDR</p> -<li><p>Register : ddrc_ctrl @ 0XF8006000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_soft_rstb</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_powerdown_en</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_data_bus_width</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_burst8_refresh</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rdwr_idle_gap</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_ddrc_dis_rd_bypass</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_act_bypass</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_auto_refresh</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ddrc_ctrl @ 0XF8006000</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>81</b></td></tr></table> -</li> -</ul> -<h2>CHECK DDR STATUS</h2> -<ul> -<p>CHECK DDR STATUS</p> -<li><p>Register : mode_sts_reg @ 0XF8006054</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >ddrc_reg_operating_mode</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>mode_sts_reg @ 0XF8006054</td><td></td><td class="hex"><b>7</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_mio_init_data_2_0">ps7_mio_init_data_2_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>OCM REMAPPING</h2> -<ul> -<p>OCM REMAPPING</p> -<li><p>Register : GPIOB_CTRL @ 0XF8000B00</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >VREF_EN</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >VREF_PULLUP_EN</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLK_PULLUP_EN</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SRSTN_PULLUP_EN</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>GPIOB_CTRL @ 0XF8000B00</td><td></td><td class="hex"><b>303</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DDRIOB SETTINGS</h2> -<ul> -<p>DDRIOB SETTINGS</p> -<li><p>Register : DDRIOB_ADDR0 @ 0XF8000B40</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_ADDR0 @ 0XF8000B40</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_ADDR1 @ 0XF8000B44</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_ADDR1 @ 0XF8000B44</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA0 @ 0XF8000B48</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DATA0 @ 0XF8000B48</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>672</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA1 @ 0XF8000B4C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DATA1 @ 0XF8000B4C</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>672</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF0 @ 0XF8000B50</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">2</td><td class="hex">4</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DIFF0 @ 0XF8000B50</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>674</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF1 @ 0XF8000B54</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">2</td><td class="hex">4</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DIFF1 @ 0XF8000B54</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>674</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_CLOCK @ 0XF8000B58</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_POWER</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCR_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_CLOCK @ 0XF8000B58</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_ADDR @ 0XF8000B5C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">1a</td><td class="hex">68000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1a</td><td class="hex">d00000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_ADDR @ 0XF8000B5C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>d6861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_DATA @ 0XF8000B60</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">6</td><td class="hex">18000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1f</td><td class="hex">f80000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_DATA @ 0XF8000B60</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>f9861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_DIFF @ 0XF8000B64</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">6</td><td class="hex">18000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1f</td><td class="hex">f80000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_DIFF @ 0XF8000B64</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>f9861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DRIVE_SLEW_CLOCK @ 0XF8000B68</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DRIVE_P</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">1c</td><td class="hex">1c</td></tr> -<tr><td >DRIVE_N</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">c</td><td class="hex">600</td></tr> -<tr><td >SLEW_P</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">1a</td><td class="hex">68000</td></tr> -<tr><td >SLEW_N</td><td class="hex">23:19</td><td class="hex">f80000</td><td class="hex">1a</td><td class="hex">d00000</td></tr> -<tr><td >GTL</td><td class="hex">26:24</td><td class="hex">7000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RTERM</td><td class="hex">31:27</td><td class="hex">f8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DRIVE_SLEW_CLOCK @ 0XF8000B68</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>d6861c</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DDR_CTRL @ 0XF8000B6C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >VREF_INT_EN</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VREF_SEL</td><td class="hex">4:1</td><td class="hex">1e</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VREF_EXT_EN</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >VREF_PULLUP_EN</td><td class="hex">8:7</td><td class="hex">180</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >REFIO_EN</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >REFIO_TEST</td><td class="hex">11:10</td><td class="hex">c00</td><td class="hex">3</td><td class="hex">c00</td></tr> -<tr><td >REFIO_PULLUP_EN</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DRST_B_PULLUP_EN</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CKE_PULLUP_EN</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DDR_CTRL @ 0XF8000B6C</td><td></td><td class="hex"><b>7fff</b></td><td></td><td class="hex"><b>e60</b></td></tr></table> -</li> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >VRN_OUT</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">1</td><td class="hex">20</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>21</b></td><td></td><td class="hex"><b>21</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRN_OUT</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">1</td><td class="hex">20</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>21</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -</ul> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >ENABLE</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >VRP_TRI</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRN_TRI</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRP_OUT</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VRN_OUT</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">1</td><td class="hex">20</td></tr> -<tr><td >NREF_OPT1</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NREF_OPT2</td><td class="hex">10:8</td><td class="hex">700</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NREF_OPT4</td><td class="hex">13:11</td><td class="hex">3800</td><td class="hex">1</td><td class="hex">800</td></tr> -<tr><td >PREF_OPT1</td><td class="hex">16:14</td><td class="hex">1c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PREF_OPT2</td><td class="hex">19:17</td><td class="hex">e0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >UPDATE_CONTROL</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INIT_COMPLETE</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_CLK</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_HLN</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_HLP</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TST_RST</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >INT_DCI_EN</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>7ffffff</b></td><td></td><td class="hex"><b>823</b></td></tr></table> -</li> -</ul> -<h2>MIO PROGRAMMING</h2> -<ul> -<p>MIO PROGRAMMING</p> -<li><p>Register : MIO_PIN_00 @ 0XF8000700</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_00 @ 0XF8000700</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_01 @ 0XF8000704</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_01 @ 0XF8000704</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_02 @ 0XF8000708</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_02 @ 0XF8000708</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_03 @ 0XF800070C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_03 @ 0XF800070C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_04 @ 0XF8000710</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_04 @ 0XF8000710</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_05 @ 0XF8000714</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_05 @ 0XF8000714</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_06 @ 0XF8000718</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_06 @ 0XF8000718</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_07 @ 0XF800071C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_07 @ 0XF800071C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_08 @ 0XF8000720</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_08 @ 0XF8000720</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_09 @ 0XF8000724</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_09 @ 0XF8000724</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_10 @ 0XF8000728</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_10 @ 0XF8000728</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>1640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_11 @ 0XF800072C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_11 @ 0XF800072C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>1640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_12 @ 0XF8000730</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_12 @ 0XF8000730</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_13 @ 0XF8000734</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_13 @ 0XF8000734</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_14 @ 0XF8000738</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_14 @ 0XF8000738</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_15 @ 0XF800073C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_15 @ 0XF800073C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_16 @ 0XF8000740</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_16 @ 0XF8000740</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_17 @ 0XF8000744</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_17 @ 0XF8000744</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_18 @ 0XF8000748</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_18 @ 0XF8000748</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_19 @ 0XF800074C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_19 @ 0XF800074C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_20 @ 0XF8000750</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_20 @ 0XF8000750</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_21 @ 0XF8000754</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_21 @ 0XF8000754</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_22 @ 0XF8000758</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_22 @ 0XF8000758</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_23 @ 0XF800075C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_23 @ 0XF800075C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_24 @ 0XF8000760</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_24 @ 0XF8000760</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_25 @ 0XF8000764</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_25 @ 0XF8000764</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_26 @ 0XF8000768</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_26 @ 0XF8000768</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_27 @ 0XF800076C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_27 @ 0XF800076C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_28 @ 0XF8000770</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_28 @ 0XF8000770</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_29 @ 0XF8000774</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_29 @ 0XF8000774</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_30 @ 0XF8000778</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_30 @ 0XF8000778</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_31 @ 0XF800077C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_31 @ 0XF800077C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_32 @ 0XF8000780</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_32 @ 0XF8000780</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_33 @ 0XF8000784</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_33 @ 0XF8000784</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_34 @ 0XF8000788</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_34 @ 0XF8000788</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_35 @ 0XF800078C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_35 @ 0XF800078C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_36 @ 0XF8000790</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_36 @ 0XF8000790</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_37 @ 0XF8000794</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_37 @ 0XF8000794</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_38 @ 0XF8000798</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_38 @ 0XF8000798</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_39 @ 0XF800079C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_39 @ 0XF800079C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_40 @ 0XF80007A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_40 @ 0XF80007A0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_41 @ 0XF80007A4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_41 @ 0XF80007A4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_42 @ 0XF80007A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_42 @ 0XF80007A8</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_43 @ 0XF80007AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_43 @ 0XF80007AC</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_44 @ 0XF80007B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_44 @ 0XF80007B0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_45 @ 0XF80007B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_45 @ 0XF80007B4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_46 @ 0XF80007B8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_46 @ 0XF80007B8</td><td></td><td class="hex"><b>3f01</b></td><td></td><td class="hex"><b>200</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_47 @ 0XF80007BC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_47 @ 0XF80007BC</td><td></td><td class="hex"><b>3f01</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_48 @ 0XF80007C0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_48 @ 0XF80007C0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2e0</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_49 @ 0XF80007C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_49 @ 0XF80007C4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2e1</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_50 @ 0XF80007C8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_50 @ 0XF80007C8</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_51 @ 0XF80007CC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_51 @ 0XF80007CC</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_52 @ 0XF80007D0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_52 @ 0XF80007D0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>280</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_53 @ 0XF80007D4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_53 @ 0XF80007D4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>280</b></td></tr></table> -</li> -<li><p>Register : SD0_WP_CD_SEL @ 0XF8000830</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SDIO0_CD_SEL</td><td class="hex">21:16</td><td class="hex">3f0000</td><td class="hex">2f</td><td class="hex">2f0000</td></tr> -<tr><td><b>SD0_WP_CD_SEL @ 0XF8000830</td><td></td><td class="hex"><b>3f0000</b></td><td></td><td class="hex"><b>2f0000</b></td></tr></table> -</li> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_peripherals_init_data_2_0">ps7_peripherals_init_data_2_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>DDR TERM/IBUF_DISABLE_MODE SETTINGS</h2> -<ul> -<p>DDR TERM/IBUF_DISABLE_MODE SETTINGS</p> -<li><p>Register : DDRIOB_DATA0 @ 0XF8000B48</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DATA0 @ 0XF8000B48</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA1 @ 0XF8000B4C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DATA1 @ 0XF8000B4C</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF0 @ 0XF8000B50</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DIFF0 @ 0XF8000B50</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF1 @ 0XF8000B54</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DIFF1 @ 0XF8000B54</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -<h2>SRAM/NOR SET OPMODE</h2> -<ul> -<p>SRAM/NOR SET OPMODE</p> -</ul> -<h2>UART REGISTERS</h2> -<ul> -<p>UART REGISTERS</p> -<li><p>Register : Baud_rate_divider_reg0 @ 0XE0001034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >BDIV</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td><b>Baud_rate_divider_reg0 @ 0XE0001034</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>6</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_gen_reg0 @ 0XE0001018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CD</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">3e</td><td class="hex">3e</td></tr> -<tr><td><b>Baud_rate_gen_reg0 @ 0XE0001018</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : Control_reg0 @ 0XE0001000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STPBRK</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STTBRK</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RSTTO</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXDIS</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXEN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >RXDIS</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RXEN</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >TXRES</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >RXRES</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>Control_reg0 @ 0XE0001000</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>17</b></td></tr></table> -</li> -<li><p>Register : mode_reg0 @ 0XE0001004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IRMODE</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >UCLKEN</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CHMODE</td><td class="hex">9:8</td><td class="hex">300</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NBSTOP</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PAR</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">4</td><td class="hex">20</td></tr> -<tr><td >CHRL</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLKS</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>mode_reg0 @ 0XE0001004</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_divider_reg0 @ 0XE0000034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >BDIV</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td><b>Baud_rate_divider_reg0 @ 0XE0000034</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>6</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_gen_reg0 @ 0XE0000018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CD</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">3e</td><td class="hex">3e</td></tr> -<tr><td><b>Baud_rate_gen_reg0 @ 0XE0000018</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : Control_reg0 @ 0XE0000000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STPBRK</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STTBRK</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RSTTO</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXDIS</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXEN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >RXDIS</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RXEN</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >TXRES</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >RXRES</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>Control_reg0 @ 0XE0000000</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>17</b></td></tr></table> -</li> -<li><p>Register : mode_reg0 @ 0XE0000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IRMODE</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >UCLKEN</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CHMODE</td><td class="hex">9:8</td><td class="hex">300</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NBSTOP</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PAR</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">4</td><td class="hex">20</td></tr> -<tr><td >CHRL</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLKS</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>mode_reg0 @ 0XE0000004</td><td></td><td class="hex"><b>fff</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -</ul> -<h2>QSPI REGISTERS</h2> -<ul> -<p>QSPI REGISTERS</p> -<li><p>Register : Config_reg @ 0XE000D000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Holdb_dr</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>Config_reg @ 0XE000D000</td><td></td><td class="hex"><b>80000</b></td><td></td><td class="hex"><b>80000</b></td></tr></table> -</li> -</ul> -<h2>PL POWER ON RESET REGISTERS</h2> -<ul> -<p>PL POWER ON RESET REGISTERS</p> -<li><p>Register : CTRL @ 0XF8007000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PCFG_POR_CNT_4K</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CTRL @ 0XF8007000</td><td></td><td class="hex"><b>20000000</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>SMC TIMING CALCULATION REGISTER UPDATE</h2> -<ul> -<p>SMC TIMING CALCULATION REGISTER UPDATE</p> -<h2>NAND SET CYCLE</h2> -<ul> -<p>NAND SET CYCLE</p> -</ul> -<h2>OPMODE</h2> -<ul> -<p>OPMODE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>SRAM/NOR CS0 SET CYCLE</h2> -<ul> -<p>SRAM/NOR CS0 SET CYCLE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>NOR CS0 BASE ADDRESS</h2> -<ul> -<p>NOR CS0 BASE ADDRESS</p> -</ul> -<h2>SRAM/NOR CS1 SET CYCLE</h2> -<ul> -<p>SRAM/NOR CS1 SET CYCLE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>NOR CS1 BASE ADDRESS</h2> -<ul> -<p>NOR CS1 BASE ADDRESS</p> -</ul> -<h2>USB RESET</h2> -<ul> -<p>USB RESET</p> -<h2>DIR MODE BANK 0</h2> -<ul> -<p>DIR MODE BANK 0</p> -</ul> -<h2>DIR MODE BANK 1</h2> -<ul> -<p>DIR MODE BANK 1</p> -<li><p>Register : DIRM_1 @ 0XE000A244</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DIRECTION_1</td><td class="hex">21:0</td><td class="hex">3fffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>DIRM_1 @ 0XE000A244</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE BANK 0</h2> -<ul> -<p>OUTPUT ENABLE BANK 0</p> -</ul> -<h2>OUTPUT ENABLE BANK 1</h2> -<ul> -<p>OUTPUT ENABLE BANK 1</p> -<li><p>Register : OEN_1 @ 0XE000A248</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >OP_ENABLE_1</td><td class="hex">21:0</td><td class="hex">3fffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>OEN_1 @ 0XE000A248</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff0000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -<h2>ENET RESET</h2> -<ul> -<p>ENET RESET</p> -<h2>DIR MODE BANK 0</h2> -<ul> -<p>DIR MODE BANK 0</p> -</ul> -<h2>DIR MODE BANK 1</h2> -<ul> -<p>DIR MODE BANK 1</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE BANK 0</h2> -<ul> -<p>OUTPUT ENABLE BANK 0</p> -</ul> -<h2>OUTPUT ENABLE BANK 1</h2> -<ul> -<p>OUTPUT ENABLE BANK 1</p> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -<h2>I2C RESET</h2> -<ul> -<p>I2C RESET</p> -<h2>DIR MODE GPIO BANK0</h2> -<ul> -<p>DIR MODE GPIO BANK0</p> -</ul> -<h2>DIR MODE GPIO BANK1</h2> -<ul> -<p>DIR MODE GPIO BANK1</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE</h2> -<ul> -<p>OUTPUT ENABLE</p> -</ul> -<h2>OUTPUT ENABLE</h2> -<ul> -<p>OUTPUT ENABLE</p> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -</ul> -</ul> -<hr/> -<h1><a name="ps7_post_config_2_0">ps7_post_config_2_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>ENABLING LEVEL SHIFTER</h2> -<ul> -<p>ENABLING LEVEL SHIFTER</p> -<li><p>Register : LVL_SHFTR_EN @ 0XF8000900</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >USER_INP_ICT_EN_0</td><td class="hex">1:0</td><td class="hex">3</td><td class="hex">3</td><td class="hex">3</td></tr> -<tr><td >USER_INP_ICT_EN_1</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">3</td><td class="hex">c</td></tr> -<tr><td><b>LVL_SHFTR_EN @ 0XF8000900</td><td></td><td class="hex"><b>f</b></td><td></td><td class="hex"><b>f</b></td></tr></table> -</li> -</ul> -<h2>FPGA RESETS TO 1</h2> -<ul> -<p>FPGA RESETS TO 1</p> -<li><p>Register : FPGA_RST_CTRL @ 0XF8000240</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reserved_3</td><td class="hex">31:25</td><td class="hex">fe000000</td><td class="hex">7f</td><td class="hex">fe000000</td></tr> -<tr><td >FPGA_ACP_RST</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td >FPGA_AXDS3_RST</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">1</td><td class="hex">800000</td></tr> -<tr><td >FPGA_AXDS2_RST</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">1</td><td class="hex">400000</td></tr> -<tr><td >FPGA_AXDS1_RST</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >FPGA_AXDS0_RST</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td >reserved_2</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">3</td><td class="hex">c0000</td></tr> -<tr><td >FSSW1_FPGA_RST</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">1</td><td class="hex">20000</td></tr> -<tr><td >FSSW0_FPGA_RST</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reserved_1</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">3</td><td class="hex">c000</td></tr> -<tr><td >FPGA_FMSW1_RST</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td >FPGA_FMSW0_RST</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >FPGA_DMA3_RST</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">1</td><td class="hex">800</td></tr> -<tr><td >FPGA_DMA2_RST</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">1</td><td class="hex">400</td></tr> -<tr><td >FPGA_DMA1_RST</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >FPGA_DMA0_RST</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >reserved</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">f</td><td class="hex">f0</td></tr> -<tr><td >FPGA3_OUT_RST</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >FPGA2_OUT_RST</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >FPGA1_OUT_RST</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >FPGA0_OUT_RST</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>FPGA_RST_CTRL @ 0XF8000240</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>ffffffff</b></td></tr></table> -</li> -</ul> -<h2>FPGA RESETS TO 0</h2> -<ul> -<p>FPGA RESETS TO 0</p> -<li><p>Register : FPGA_RST_CTRL @ 0XF8000240</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reserved_3</td><td class="hex">31:25</td><td class="hex">fe000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_ACP_RST</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS3_RST</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS2_RST</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS1_RST</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_AXDS0_RST</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_2</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FSSW1_FPGA_RST</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FSSW0_FPGA_RST</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_1</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_FMSW1_RST</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_FMSW0_RST</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA3_RST</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA2_RST</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA1_RST</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA_DMA0_RST</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA3_OUT_RST</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA2_OUT_RST</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA1_OUT_RST</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA0_OUT_RST</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>FPGA_RST_CTRL @ 0XF8000240</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>AFI REGISTERS</h2> -<ul> -<p>AFI REGISTERS</p> -<h2>AFI0 REGISTERS</h2> -<ul> -<p>AFI0 REGISTERS</p> -</ul> -<h2>AFI1 REGISTERS</h2> -<ul> -<p>AFI1 REGISTERS</p> -</ul> -<h2>AFI2 REGISTERS</h2> -<ul> -<p>AFI2 REGISTERS</p> -</ul> -<h2>AFI3 REGISTERS</h2> -<ul> -<p>AFI3 REGISTERS</p> -</ul> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -</body> -</html> -<!DOCTYPE html> -<html lang="en"> -<head> -<meta http-equiv="content-type" content="text/html;charset=UTF-8"/> -<title>Zynq PS configuration detail</title> -<style type="text/css"> -.hex {font-family:monospace ; text-align : right} -td { min-width : 80px ; } -</style> -</head> -<body> -<p style="height: 7px">Following peripherals are selected in the design. </p> -<p><br /></p> -<h2><a name="Top">Peripheral Selected</a></h2> -<ul> -<li>Quad SPI Flash</li> -<li>Enet 0</li> -<li>USB 0</li> -<li>SD 0</li> -<li>UART 0</li> -<li>UART 1</li> -<li>I2C 0</li> -<li>I2C 1</li> -<li>GPIO</li> -</ul> -<p>To see detailed information please follow below links:</p> -<ul> -<li><a href="#MIOConfTab">MIO Configuration Table</a></li> -<li><a href="#ZynqPerTab">Zynq Peripheral Configuration</a></li> -<li><a href="#DDRInfoTab">DDR Configuration Information</a></li> -<li>SLCR settings</li> -<ul> -<li><a href="#ps7_pll_init_data">PLL Init Data</a></li> -<li><a href="#ps7_clock_init_data">Clock Init Data</a></li> -<li><a href="#ps7_ddr_init_data">DDR Init Data</a></li> -<li><a href="#ps7_mio_init_data">MIO Init Data</a></li> -</ul> -</ul> -<h2><a name="MIOConfTab">MIO configuration Table</a></h2> -<ul><table border="1"> -<thead><tr> <th>MIO Pin</th> <th>Peripheral</th> <th>Signal</th> <th>IO type</th> <th>Speed</th> <th>Pullup</th> <th>Direction</th> </tr></thead> -<tr bgcolor="#FA4A46"><td><a name="MIO 0">MIO 0</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[0]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 1">MIO 1</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_ss_b</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 2">MIO 2</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[0]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 3">MIO 3</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[1]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 4">MIO 4</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[2]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 5">MIO 5</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_io[3]</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 6">MIO 6</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi0_sclk</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 7">MIO 7</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[7]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FAEBD7"><td><a name="MIO 8">MIO 8</a></td><td><a href="#Quad SPI Flash">Quad SPI Flash</a></td><td>qspi_fbclk</td><td>LVCMOS 3.3V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 9">MIO 9</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[9]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 10">MIO 10</a></td><td><a href="#I2C 0">I2C 0</a></td><td>scl</td><td>LVCMOS 3.3V</td><td>slow</td><td>enabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 11">MIO 11</a></td><td><a href="#I2C 0">I2C 0</a></td><td>sda</td><td>LVCMOS 3.3V</td><td>slow</td><td>enabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 12">MIO 12</a></td><td><a href="#I2C 1">I2C 1</a></td><td>scl</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#BDB76B"><td><a name="MIO 13">MIO 13</a></td><td><a href="#I2C 1">I2C 1</a></td><td>sda</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 14">MIO 14</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[14]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 15">MIO 15</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[15]</td><td>LVCMOS 3.3V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 16">MIO 16</a></td><td><a href="#Enet 0">Enet 0</a></td><td>tx_clk</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 17">MIO 17</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[0]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 18">MIO 18</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[1]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 19">MIO 19</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[2]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 20">MIO 20</a></td><td><a href="#Enet 0">Enet 0</a></td><td>txd[3]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 21">MIO 21</a></td><td><a href="#Enet 0">Enet 0</a></td><td>tx_ctl</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 22">MIO 22</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rx_clk</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 23">MIO 23</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[0]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 24">MIO 24</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[1]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 25">MIO 25</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[2]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 26">MIO 26</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rxd[3]</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 27">MIO 27</a></td><td><a href="#Enet 0">Enet 0</a></td><td>rx_ctl</td><td>HSTL 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 28">MIO 28</a></td><td><a href="#USB 0">USB 0</a></td><td>data[4]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 29">MIO 29</a></td><td><a href="#USB 0">USB 0</a></td><td>dir</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 30">MIO 30</a></td><td><a href="#USB 0">USB 0</a></td><td>stp</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 31">MIO 31</a></td><td><a href="#USB 0">USB 0</a></td><td>nxt</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 32">MIO 32</a></td><td><a href="#USB 0">USB 0</a></td><td>data[0]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 33">MIO 33</a></td><td><a href="#USB 0">USB 0</a></td><td>data[1]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 34">MIO 34</a></td><td><a href="#USB 0">USB 0</a></td><td>data[2]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 35">MIO 35</a></td><td><a href="#USB 0">USB 0</a></td><td>data[3]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 36">MIO 36</a></td><td><a href="#USB 0">USB 0</a></td><td>clk</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 37">MIO 37</a></td><td><a href="#USB 0">USB 0</a></td><td>data[5]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 38">MIO 38</a></td><td><a href="#USB 0">USB 0</a></td><td>data[6]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 39">MIO 39</a></td><td><a href="#USB 0">USB 0</a></td><td>data[7]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 40">MIO 40</a></td><td><a href="#SD 0">SD 0</a></td><td>clk</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 41">MIO 41</a></td><td><a href="#SD 0">SD 0</a></td><td>cmd</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 42">MIO 42</a></td><td><a href="#SD 0">SD 0</a></td><td>data[0]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 43">MIO 43</a></td><td><a href="#SD 0">SD 0</a></td><td>data[1]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 44">MIO 44</a></td><td><a href="#SD 0">SD 0</a></td><td>data[2]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 45">MIO 45</a></td><td><a href="#SD 0">SD 0</a></td><td>data[3]</td><td>LVCMOS 1.8V</td><td>fast</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#7FFF00"><td><a name="MIO 46">MIO 46</a></td><td><a href="#USB 0">USB 0</a></td><td>reset</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -<tr bgcolor="#D2691E"><td><a name="MIO 47">MIO 47</a></td><td><a href="#SD 0">SD 0</a></td><td>cd</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#6495ED"><td><a name="MIO 48">MIO 48</a></td><td><a href="#UART 1">UART 1</a></td><td>tx</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#6495ED"><td><a name="MIO 49">MIO 49</a></td><td><a href="#UART 1">UART 1</a></td><td>rx</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 50">MIO 50</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[50]</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#FA4A46"><td><a name="MIO 51">MIO 51</a></td><td><a href="#GPIO">GPIO</a></td><td>gpio[51]</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>in</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 52">MIO 52</a></td><td><a href="#Enet 0">Enet 0</a></td><td>mdc</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>out</td></tr> -<tr bgcolor="#DEB887"><td><a name="MIO 53">MIO 53</a></td><td><a href="#Enet 0">Enet 0</a></td><td>mdio</td><td>LVCMOS 1.8V</td><td>slow</td><td>disabled</td><td>inout</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h2><a name="ZynqPerTab">Zynq Peripheral Configuration</a></h2> -<ul><table border="1"> -<tr><thead> <th>Peripheral</th> <th>Signal Group</th> <th>Signal</th> <th>MIO</th> </thead></tr> -<tr bgcolor="#FAEBD7"><td><a name="Quad SPI Flash" >Quad SPI Flash</a></td> <td></td><td></td><td>MIO 1 .. 6</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Dual Quad SPI (4 bit) </td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Dual Quad SPI (Parallel 8 bit)</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FAEBD7"><td></td><td>Feedback Clk</td><td></td><td>MIO 8</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="nor" >SRAM/NOR Flash</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FFE4C4"><td><a name="nand" >NAND Flash</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DEB887"><td><a name="Enet 0" >Enet 0</a></td> <td></td><td></td><td>MIO 16 .. 27</td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>tx_clk</td><td><a href="#MIO 16">MIO 16</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[3]</td><td><a href="#MIO 20">MIO 20</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[2]</td><td><a href="#MIO 19">MIO 19</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[1]</td><td><a href="#MIO 18">MIO 18</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>txd[0]</td><td><a href="#MIO 17">MIO 17</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>tx_ctl</td><td><a href="#MIO 21">MIO 21</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rx_clk</td><td><a href="#MIO 22">MIO 22</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[3]</td><td><a href="#MIO 26">MIO 26</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[2]</td><td><a href="#MIO 25">MIO 25</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[1]</td><td><a href="#MIO 24">MIO 24</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rxd[0]</td><td><a href="#MIO 23">MIO 23</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>rx_ctl</td><td><a href="#MIO 27">MIO 27</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td>MDIO</td><td></td><td>MIO 52 .. 53</td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>mdc</td><td><a href="#MIO 52">MIO 52</a></td></tr> -<tr bgcolor="#DEB887"><td></td><td></td><td>mdio</td><td><a href="#MIO 53">MIO 53</a></td></tr> -<tr bgcolor="#DEB887"><td><a name="enet1" >Enet 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#7FFF00"><td><a name="USB 0" >USB 0</a></td> <td></td><td></td><td>MIO 28 .. 39</td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>clk</td><td><a href="#MIO 36">MIO 36</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>dir</td><td><a href="#MIO 29">MIO 29</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>stp</td><td><a href="#MIO 30">MIO 30</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>nxt</td><td><a href="#MIO 31">MIO 31</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[0]</td><td><a href="#MIO 32">MIO 32</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[1]</td><td><a href="#MIO 33">MIO 33</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[2]</td><td><a href="#MIO 34">MIO 34</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[3]</td><td><a href="#MIO 35">MIO 35</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[4]</td><td><a href="#MIO 28">MIO 28</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[5]</td><td><a href="#MIO 37">MIO 37</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[6]</td><td><a href="#MIO 38">MIO 38</a></td></tr> -<tr bgcolor="#7FFF00"><td></td><td></td><td>data[7]</td><td><a href="#MIO 39">MIO 39</a></td></tr> -<tr bgcolor="#7FFF00"><td><a name="usb1" >USB 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#D2691E"><td><a name="SD 0" >SD 0</a></td> <td></td><td></td><td>MIO 40 .. 45</td></tr> -<tr bgcolor="#D2691E"><td></td><td>CD</td><td></td><td>MIO 47</td></tr> -<tr bgcolor="#D2691E"><td></td><td>WP</td><td></td><td>EMIO</td></tr> -<tr bgcolor="#D2691E"><td></td><td>Power</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#D2691E"><td><a name="sd1" >SD 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#6495ED"><td><a name="UART 0" >UART 0</a></td> <td></td><td></td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>rx</td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>tx</td><td>EMIO</td></tr> -<tr bgcolor="#6495ED"><td></td><td>Modem signals</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#6495ED"><td><a name="UART 1" >UART 1</a></td> <td></td><td></td><td>MIO 48 .. 49</td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>rx</td><td><a href="#MIO 49">MIO 49</a></td></tr> -<tr bgcolor="#6495ED"><td></td><td></td><td>tx</td><td><a href="#MIO 48">MIO 48</a></td></tr> -<tr bgcolor="#6495ED"><td></td><td>Modem Signals</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BDB76B"><td><a name="I2C 0" >I2C 0</a></td> <td></td><td></td><td>MIO 10 .. 11</td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>scl</td><td><a href="#MIO 10">MIO 10</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>sda</td><td><a href="#MIO 11">MIO 11</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td>Interrupt</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BDB76B"><td><a name="I2C 1" >I2C 1</a></td> <td></td><td></td><td>MIO 12 .. 13</td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>scl</td><td><a href="#MIO 12">MIO 12</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td></td><td>sda</td><td><a href="#MIO 13">MIO 13</a></td></tr> -<tr bgcolor="#BDB76B"><td></td><td>Interrupt</td><td></td><td>Disabled</td></tr> -<tr bgcolor="#8DBC8F"><td><a name="spi0" >SPI 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#8DBC8F"><td><a name="spi1" >SPI 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DAA520"><td><a name="can0" >CAN 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#DAA520"><td><a name="can1" >CAN 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#ADD8E6"><td><a name="trace" >Trace</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BC8F8F"><td><a name="ttc0" >Timer 0</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#BC8F8F"><td><a name="ttc1" >Timer 1</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FF6347"><td><a name="wdt" >Watchdog</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#EE82EE"><td><a name="pjtag" >PJTAG</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FA4A46"><td><a name="GPIO" >GPIO</a></td> <td></td><td></td><td>MIO</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="mode" >Mode</a></td> <td></td><td></td><td>Disabled</td></tr> -<tr bgcolor="#FFFFFF"><td><a name="vcfg" >VCfg</a></td> <td></td><td></td><td>Disabled</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h2><a name="DDRInfoTab">DDR Memory information</a></h2> -<h3><a name="DDRInfoTab">DDR Controller Configuration</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="Enable DDR">Enable DDR</a></td><td>1</td></tr> -<tr> <td><a name="Memory Type">Memory Type</a></td><td>DDR 3</td></tr> -<tr> <td><a name="Memory Part">Memory Part</a></td><td>MT41K128M16 JT-125</td></tr> -<tr> <td><a name="DRAM bus width">DRAM bus width</a></td><td>32 Bit</td></tr> -<tr> <td><a name="ECC">ECC</a></td><td>Disabled</td></tr> -<tr> <td><a name="BURST Length (lppdr only)">BURST Length (lppdr only)</a></td><td>8</td></tr> -<tr> <td><a name="Internal Vref">Internal Vref</a></td><td>0</td></tr> -<tr> <td><a name="Operating Frequency (MHz)">Operating Frequency (MHz)</a></td><td>525.000000</td></tr> -<tr> <td><a name="HIGH temperature">HIGH temperature</a></td><td>Normal (0-85)</td></tr> -</table></ul> -<h3><a name="DDRInfoTab">Memory Part Configuration</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="DRAM IC bus width">DRAM IC bus width</a></td><td>16 Bits</td></tr> -<tr> <td><a name="DRAM Device Capacity">DRAM Device Capacity</a></td><td>2048 MBits</td></tr> -<tr> <td><a name="Speed Bin">Speed Bin</a></td><td>DDR3_1066F</td></tr> -<tr> <td><a name="BANK Address Count">BANK Address Count</a></td><td>3</td></tr> -<tr> <td><a name="ROW Address Count">ROW Address Count</a></td><td>14</td></tr> -<tr> <td><a name="COLUMN Address Count">COLUMN Address Count</a></td><td>10</td></tr> -<tr> <td><a name="CAS Latency">CAS Latency</a></td><td>7</td></tr> -<tr> <td><a name="CAS Write Latency">CAS Write Latency</a></td><td>6</td></tr> -<tr> <td><a name="RAS to CAS Delay">RAS to CAS Delay</a></td><td>7</td></tr> -<tr> <td><a name="RECHARGE Time">RECHARGE Time</a></td><td>7</td></tr> -<tr> <td><a name="tRC (ns )">tRC (ns )</a></td><td>48.75</td></tr> -<tr> <td><a name="tRASmin ( ns )">tRASmin ( ns )</a></td><td>35.0</td></tr> -<tr> <td><a name="tFAW">tFAW</a></td><td>40.0</td></tr> -<tr> <td><a name="ADDITIVE Latency">ADDITIVE Latency</a></td><td>0</td></tr> -</table></ul> -<h3><a name="DDRInfoTab">Training/Board Details</a></h3> -<ul><table border="1"> -<tr><thead> <th>Parameter</th> <th>Value</th> </thead></tr> -<tr> <td><a name="Write levelling">Write levelling</a></td><td>1</td></tr> -<tr> <td><a name="Read gate">Read gate</a></td><td>1</td></tr> -<tr> <td><a name="Read data eye">Read data eye</a></td><td>1</td></tr> -<tr> <td><a name="DQS to Clock delay [0] (ns)">DQS to Clock delay [0] (ns)</a></td><td>-0.073</td></tr> -<tr> <td><a name="DQS to Clock delay [1] (ns)">DQS to Clock delay [1] (ns)</a></td><td>-0.034</td></tr> -<tr> <td><a name="DQS to Clock delay [2] (ns)">DQS to Clock delay [2] (ns)</a></td><td>-0.03</td></tr> -<tr> <td><a name="DQS to Clock delay [3] (ns)">DQS to Clock delay [3] (ns)</a></td><td>-0.082</td></tr> -<tr> <td><a name="Board delay [0] (ns)">Board delay [0] (ns)</a></td><td>0.176</td></tr> -<tr> <td><a name="Board delay [1] (ns)">Board delay [1] (ns)</a></td><td>0.159</td></tr> -<tr> <td><a name="Board delay [2] (ns)">Board delay [2] (ns)</a></td><td>0.162</td></tr> -<tr> <td><a name="Board delay [3] (ns)">Board delay [3] (ns)</a></td><td>0.187</td></tr> -</table></ul> -<li><a href="#Top">Go To TOP</a></li> -<h1><a name="ps7_pll_init_data_3_0">ps7_pll_init_data_3_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>PLL SLCR REGISTERS</h2> -<ul> -<p>PLL SLCR REGISTERS</p> -<h2>ARM PLL INIT</h2> -<ul> -<p>ARM PLL INIT</p> -<li><p>Register : ARM_PLL_CFG @ 0XF8000110</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">177</td><td class="hex">177000</td></tr> -<tr><td><b>ARM_PLL_CFG @ 0XF8000110</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1772c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">1a</td><td class="hex">1a000</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>1a000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >ARM_PLL_LOCK</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : ARM_PLL_CTRL @ 0XF8000100</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ARM_PLL_CTRL @ 0XF8000100</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<li><p>Register : ARM_CLK_CTRL @ 0XF8000120</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >CPU_6OR4XCLKACT</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td >CPU_3OR2XCLKACT</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">1</td><td class="hex">2000000</td></tr> -<tr><td >CPU_2XCLKACT</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">1</td><td class="hex">4000000</td></tr> -<tr><td >CPU_1XCLKACT</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">1</td><td class="hex">8000000</td></tr> -<tr><td >CPU_PERI_CLKACT</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td><b>ARM_CLK_CTRL @ 0XF8000120</td><td></td><td class="hex"><b>1f003f30</b></td><td></td><td class="hex"><b>1f000200</b></td></tr></table> -</li> -</ul> -<h2>DDR PLL INIT</h2> -<ul> -<p>DDR PLL INIT</p> -<li><p>Register : DDR_PLL_CFG @ 0XF8000114</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">1db</td><td class="hex">1db000</td></tr> -<tr><td><b>DDR_PLL_CFG @ 0XF8000114</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1db2c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">15</td><td class="hex">15000</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>15000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DDR_PLL_LOCK</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>2</b></td><td></td><td class="hex"><b>2</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : DDR_PLL_CTRL @ 0XF8000104</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDR_PLL_CTRL @ 0XF8000104</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<li><p>Register : DDR_CLK_CTRL @ 0XF8000124</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DDR_3XCLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >DDR_2XCLKACT</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DDR_3XCLK_DIVISOR</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td >DDR_2XCLK_DIVISOR</td><td class="hex">31:26</td><td class="hex">fc000000</td><td class="hex">3</td><td class="hex">c000000</td></tr> -<tr><td><b>DDR_CLK_CTRL @ 0XF8000124</td><td></td><td class="hex"><b>fff00003</b></td><td></td><td class="hex"><b>c200003</b></td></tr></table> -</li> -</ul> -<h2>IO PLL INIT</h2> -<ul> -<p>IO PLL INIT</p> -<li><p>Register : IO_PLL_CFG @ 0XF8000118</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RES</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">c</td><td class="hex">c0</td></tr> -<tr><td >PLL_CP</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >LOCK_CNT</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">1f4</td><td class="hex">1f4000</td></tr> -<tr><td><b>IO_PLL_CFG @ 0XF8000118</td><td></td><td class="hex"><b>3ffff0</b></td><td></td><td class="hex"><b>1f42c0</b></td></tr></table> -</li> -<h2>UPDATE FB_DIV</h2> -<ul> -<p>UPDATE FB_DIV</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_FDIV</td><td class="hex">18:12</td><td class="hex">7f000</td><td class="hex">14</td><td class="hex">14000</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>7f000</b></td><td></td><td class="hex"><b>14000</b></td></tr></table> -</li> -</ul> -<h2>BY PASS PLL</h2> -<ul> -<p>BY PASS PLL</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>10</b></td></tr></table> -</li> -</ul> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>CHECK PLL STATUS</h2> -<ul> -<p>CHECK PLL STATUS</p> -<li><p>Register : PLL_STATUS @ 0XF800010C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IO_PLL_LOCK</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td><b>PLL_STATUS @ 0XF800010C</td><td></td><td class="hex"><b>4</b></td><td></td><td class="hex"><b>4</b></td></tr></table> -</li> -</ul> -<h2>REMOVE PLL BY PASS</h2> -<ul> -<p>REMOVE PLL BY PASS</p> -<li><p>Register : IO_PLL_CTRL @ 0XF8000108</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PLL_BYPASS_FORCE</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>IO_PLL_CTRL @ 0XF8000108</td><td></td><td class="hex"><b>10</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -</ul> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_clock_init_data_3_0">ps7_clock_init_data_3_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>CLOCK CONTROL SLCR REGISTERS</h2> -<ul> -<p>CLOCK CONTROL SLCR REGISTERS</p> -<li><p>Register : DCI_CLK_CTRL @ 0XF8000128</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">34</td><td class="hex">3400</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td><b>DCI_CLK_CTRL @ 0XF8000128</td><td></td><td class="hex"><b>3f03f01</b></td><td></td><td class="hex"><b>203401</b></td></tr></table> -</li> -<li><p>Register : GEM0_RCLK_CTRL @ 0XF8000138</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>GEM0_RCLK_CTRL @ 0XF8000138</td><td></td><td class="hex"><b>11</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -<li><p>Register : GEM0_CLK_CTRL @ 0XF8000140</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">8</td><td class="hex">800</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>GEM0_CLK_CTRL @ 0XF8000140</td><td></td><td class="hex"><b>3f03f71</b></td><td></td><td class="hex"><b>100801</b></td></tr></table> -</li> -<li><p>Register : LQSPI_CLK_CTRL @ 0XF800014C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">5</td><td class="hex">500</td></tr> -<tr><td><b>LQSPI_CLK_CTRL @ 0XF800014C</td><td></td><td class="hex"><b>3f31</b></td><td></td><td class="hex"><b>501</b></td></tr></table> -</li> -<li><p>Register : SDIO_CLK_CTRL @ 0XF8000150</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT0</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >CLKACT1</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">14</td><td class="hex">1400</td></tr> -<tr><td><b>SDIO_CLK_CTRL @ 0XF8000150</td><td></td><td class="hex"><b>3f33</b></td><td></td><td class="hex"><b>1401</b></td></tr></table> -</li> -<li><p>Register : UART_CLK_CTRL @ 0XF8000154</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT0</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >CLKACT1</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">14</td><td class="hex">1400</td></tr> -<tr><td><b>UART_CLK_CTRL @ 0XF8000154</td><td></td><td class="hex"><b>3f33</b></td><td></td><td class="hex"><b>1403</b></td></tr></table> -</li> -<li><p>Register : PCAP_CLK_CTRL @ 0XF8000168</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">5</td><td class="hex">500</td></tr> -<tr><td><b>PCAP_CLK_CTRL @ 0XF8000168</td><td></td><td class="hex"><b>3f31</b></td><td></td><td class="hex"><b>501</b></td></tr></table> -</li> -<li><p>Register : FPGA0_CLK_CTRL @ 0XF8000170</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">a</td><td class="hex">a00</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA0_CLK_CTRL @ 0XF8000170</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100a00</b></td></tr></table> -</li> -<li><p>Register : FPGA1_CLK_CTRL @ 0XF8000180</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">3</td><td class="hex">30</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">6</td><td class="hex">600</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA1_CLK_CTRL @ 0XF8000180</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100630</b></td></tr></table> -</li> -<li><p>Register : FPGA2_CLK_CTRL @ 0XF8000190</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">2</td><td class="hex">20</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">35</td><td class="hex">3500</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">2</td><td class="hex">200000</td></tr> -<tr><td><b>FPGA2_CLK_CTRL @ 0XF8000190</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>203520</b></td></tr></table> -</li> -<li><p>Register : FPGA3_CLK_CTRL @ 0XF80001A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SRCSEL</td><td class="hex">5:4</td><td class="hex">30</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DIVISOR0</td><td class="hex">13:8</td><td class="hex">3f00</td><td class="hex">a</td><td class="hex">a00</td></tr> -<tr><td >DIVISOR1</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td><b>FPGA3_CLK_CTRL @ 0XF80001A0</td><td></td><td class="hex"><b>3f03f30</b></td><td></td><td class="hex"><b>100a00</b></td></tr></table> -</li> -<li><p>Register : CLK_621_TRUE @ 0XF80001C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CLK_621_TRUE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>CLK_621_TRUE @ 0XF80001C4</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -<li><p>Register : APER_CLK_CTRL @ 0XF800012C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DMA_CPU_2XCLKACT</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >USB0_CPU_1XCLKACT</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >USB1_CPU_1XCLKACT</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >GEM0_CPU_1XCLKACT</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">1</td><td class="hex">40</td></tr> -<tr><td >GEM1_CPU_1XCLKACT</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SDI0_CPU_1XCLKACT</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">1</td><td class="hex">400</td></tr> -<tr><td >SDI1_CPU_1XCLKACT</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SPI0_CPU_1XCLKACT</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >SPI1_CPU_1XCLKACT</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CAN0_CPU_1XCLKACT</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CAN1_CPU_1XCLKACT</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >I2C0_CPU_1XCLKACT</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">1</td><td class="hex">40000</td></tr> -<tr><td >I2C1_CPU_1XCLKACT</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td >UART0_CPU_1XCLKACT</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td >UART1_CPU_1XCLKACT</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >GPIO_CPU_1XCLKACT</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">1</td><td class="hex">400000</td></tr> -<tr><td >LQSPI_CPU_1XCLKACT</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">1</td><td class="hex">800000</td></tr> -<tr><td >SMC_CPU_1XCLKACT</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td><b>APER_CLK_CTRL @ 0XF800012C</td><td></td><td class="hex"><b>1ffcccd</b></td><td></td><td class="hex"><b>1fc044d</b></td></tr></table> -</li> -</ul> -<h2>THIS SHOULD BE BLANK</h2> -<ul> -<p>THIS SHOULD BE BLANK</p> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_ddr_init_data_3_0">ps7_ddr_init_data_3_0</a></h1> -<ul> -<h2>DDR INITIALIZATION</h2> -<ul> -<p>DDR INITIALIZATION</p> -<h2>LOCK DDR</h2> -<ul> -<p>LOCK DDR</p> -<li><p>Register : ddrc_ctrl @ 0XF8006000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_soft_rstb</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_powerdown_en</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_data_bus_width</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_burst8_refresh</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rdwr_idle_gap</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_ddrc_dis_rd_bypass</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_act_bypass</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_auto_refresh</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ddrc_ctrl @ 0XF8006000</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>80</b></td></tr></table> -</li> -</ul> -<li><p>Register : Two_rank_cfg @ 0XF8006004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_rfc_nom_x32</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">7f</td><td class="hex">7f</td></tr> -<tr><td >reserved_reg_ddrc_active_ranks</td><td class="hex">13:12</td><td class="hex">3000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >reg_ddrc_addrmap_cs_bit0</td><td class="hex">18:14</td><td class="hex">7c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>Two_rank_cfg @ 0XF8006004</td><td></td><td class="hex"><b>7ffff</b></td><td></td><td class="hex"><b>107f</b></td></tr></table> -</li> -<li><p>Register : HPR_reg @ 0XF8006008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_hpr_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">f</td><td class="hex">f</td></tr> -<tr><td >reg_ddrc_hpr_max_starve_x32</td><td class="hex">21:11</td><td class="hex">3ff800</td><td class="hex">f</td><td class="hex">7800</td></tr> -<tr><td >reg_ddrc_hpr_xact_run_length</td><td class="hex">25:22</td><td class="hex">3c00000</td><td class="hex">f</td><td class="hex">3c00000</td></tr> -<tr><td><b>HPR_reg @ 0XF8006008</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>3c0780f</b></td></tr></table> -</li> -<li><p>Register : LPR_reg @ 0XF800600C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_lpr_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_lpr_max_starve_x32</td><td class="hex">21:11</td><td class="hex">3ff800</td><td class="hex">2</td><td class="hex">1000</td></tr> -<tr><td >reg_ddrc_lpr_xact_run_length</td><td class="hex">25:22</td><td class="hex">3c00000</td><td class="hex">8</td><td class="hex">2000000</td></tr> -<tr><td><b>LPR_reg @ 0XF800600C</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>2001001</b></td></tr></table> -</li> -<li><p>Register : WR_reg @ 0XF8006010</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_w_min_non_critical_x32</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_w_xact_run_length</td><td class="hex">14:11</td><td class="hex">7800</td><td class="hex">8</td><td class="hex">4000</td></tr> -<tr><td >reg_ddrc_w_max_starve_x32</td><td class="hex">25:15</td><td class="hex">3ff8000</td><td class="hex">2</td><td class="hex">10000</td></tr> -<tr><td><b>WR_reg @ 0XF8006010</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>14001</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg0 @ 0XF8006014</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_rc</td><td class="hex">5:0</td><td class="hex">3f</td><td class="hex">1a</td><td class="hex">1a</td></tr> -<tr><td >reg_ddrc_t_rfc_min</td><td class="hex">13:6</td><td class="hex">3fc0</td><td class="hex">54</td><td class="hex">1500</td></tr> -<tr><td >reg_ddrc_post_selfref_gap_x32</td><td class="hex">20:14</td><td class="hex">1fc000</td><td class="hex">10</td><td class="hex">40000</td></tr> -<tr><td><b>DRAM_param_reg0 @ 0XF8006014</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>4151a</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg1 @ 0XF8006018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_wr2pre</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">12</td><td class="hex">12</td></tr> -<tr><td >reg_ddrc_powerdown_to_x32</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">6</td><td class="hex">c0</td></tr> -<tr><td >reg_ddrc_t_faw</td><td class="hex">15:10</td><td class="hex">fc00</td><td class="hex">15</td><td class="hex">5400</td></tr> -<tr><td >reg_ddrc_t_ras_max</td><td class="hex">21:16</td><td class="hex">3f0000</td><td class="hex">23</td><td class="hex">230000</td></tr> -<tr><td >reg_ddrc_t_ras_min</td><td class="hex">26:22</td><td class="hex">7c00000</td><td class="hex">13</td><td class="hex">4c00000</td></tr> -<tr><td >reg_ddrc_t_cke</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">4</td><td class="hex">40000000</td></tr> -<tr><td><b>DRAM_param_reg1 @ 0XF8006018</td><td></td><td class="hex"><b>f7ffffff</b></td><td></td><td class="hex"><b>44e354d2</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg2 @ 0XF800601C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_write_latency</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">5</td><td class="hex">5</td></tr> -<tr><td >reg_ddrc_rd2wr</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >reg_ddrc_wr2rd</td><td class="hex">14:10</td><td class="hex">7c00</td><td class="hex">e</td><td class="hex">3800</td></tr> -<tr><td >reg_ddrc_t_xp</td><td class="hex">19:15</td><td class="hex">f8000</td><td class="hex">4</td><td class="hex">20000</td></tr> -<tr><td >reg_ddrc_pad_pd</td><td class="hex">22:20</td><td class="hex">700000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rd2pre</td><td class="hex">27:23</td><td class="hex">f800000</td><td class="hex">4</td><td class="hex">2000000</td></tr> -<tr><td >reg_ddrc_t_rcd</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">7</td><td class="hex">70000000</td></tr> -<tr><td><b>DRAM_param_reg2 @ 0XF800601C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>720238e5</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg3 @ 0XF8006020</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_ccd</td><td class="hex">4:2</td><td class="hex">1c</td><td class="hex">4</td><td class="hex">10</td></tr> -<tr><td >reg_ddrc_t_rrd</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">6</td><td class="hex">c0</td></tr> -<tr><td >reg_ddrc_refresh_margin</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >reg_ddrc_t_rp</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">7</td><td class="hex">7000</td></tr> -<tr><td >reg_ddrc_refresh_to_x32</td><td class="hex">20:16</td><td class="hex">1f0000</td><td class="hex">8</td><td class="hex">80000</td></tr> -<tr><td >reg_ddrc_mobile</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_en_dfi_dram_clk_disable</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_read_latency</td><td class="hex">28:24</td><td class="hex">1f000000</td><td class="hex">7</td><td class="hex">7000000</td></tr> -<tr><td >reg_phy_mode_ddr1_ddr2</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">1</td><td class="hex">20000000</td></tr> -<tr><td >reg_ddrc_dis_pad_pd</td><td class="hex">30:30</td><td class="hex">40000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_param_reg3 @ 0XF8006020</td><td></td><td class="hex"><b>7fdffffc</b></td><td></td><td class="hex"><b>270872d0</b></td></tr></table> -</li> -<li><p>Register : DRAM_param_reg4 @ 0XF8006024</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_en_2t_timing_mode</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_prefer_write</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_wr</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_addr</td><td class="hex">8:7</td><td class="hex">180</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_data</td><td class="hex">24:9</td><td class="hex">1fffe00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ddrc_reg_mr_wr_busy</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_type</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr_rdata_valid</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_param_reg4 @ 0XF8006024</td><td></td><td class="hex"><b>fffffc3</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : DRAM_init_param @ 0XF8006028</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_final_wait_x32</td><td class="hex">6:0</td><td class="hex">7f</td><td class="hex">7</td><td class="hex">7</td></tr> -<tr><td >reg_ddrc_pre_ocd_x32</td><td class="hex">10:7</td><td class="hex">780</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_t_mrd</td><td class="hex">13:11</td><td class="hex">3800</td><td class="hex">4</td><td class="hex">2000</td></tr> -<tr><td><b>DRAM_init_param @ 0XF8006028</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2007</b></td></tr></table> -</li> -<li><p>Register : DRAM_EMR_reg @ 0XF800602C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_emr2</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">8</td><td class="hex">8</td></tr> -<tr><td >reg_ddrc_emr3</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_EMR_reg @ 0XF800602C</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>8</b></td></tr></table> -</li> -<li><p>Register : DRAM_EMR_MR_reg @ 0XF8006030</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_mr</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">930</td><td class="hex">930</td></tr> -<tr><td >reg_ddrc_emr</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">4</td><td class="hex">40000</td></tr> -<tr><td><b>DRAM_EMR_MR_reg @ 0XF8006030</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>40930</b></td></tr></table> -</li> -<li><p>Register : DRAM_burst8_rdwr @ 0XF8006034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_burst_rdwr</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">4</td><td class="hex">4</td></tr> -<tr><td >reg_ddrc_pre_cke_x1024</td><td class="hex">13:4</td><td class="hex">3ff0</td><td class="hex">101</td><td class="hex">1010</td></tr> -<tr><td >reg_ddrc_post_cke_x1024</td><td class="hex">25:16</td><td class="hex">3ff0000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_ddrc_burstchop</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_burst8_rdwr @ 0XF8006034</td><td></td><td class="hex"><b>13ff3fff</b></td><td></td><td class="hex"><b>11014</b></td></tr></table> -</li> -<li><p>Register : DRAM_disable_DQ @ 0XF8006038</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_force_low_pri_n</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_dq</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_disable_DQ @ 0XF8006038</td><td></td><td class="hex"><b>3</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_bank @ 0XF800603C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_bank_b0</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">7</td><td class="hex">7</td></tr> -<tr><td >reg_ddrc_addrmap_bank_b1</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">7</td><td class="hex">70</td></tr> -<tr><td >reg_ddrc_addrmap_bank_b2</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">7</td><td class="hex">700</td></tr> -<tr><td >reg_ddrc_addrmap_col_b5</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b6</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DRAM_addr_map_bank @ 0XF800603C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>777</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_col @ 0XF8006040</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_col_b2</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b3</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b4</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b7</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b8</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_addrmap_col_b9</td><td class="hex">23:20</td><td class="hex">f00000</td><td class="hex">f</td><td class="hex">f00000</td></tr> -<tr><td >reg_ddrc_addrmap_col_b10</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">f</td><td class="hex">f000000</td></tr> -<tr><td >reg_ddrc_addrmap_col_b11</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">f</td><td class="hex">f0000000</td></tr> -<tr><td><b>DRAM_addr_map_col @ 0XF8006040</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>fff00000</b></td></tr></table> -</li> -<li><p>Register : DRAM_addr_map_row @ 0XF8006044</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_addrmap_row_b0</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td >reg_ddrc_addrmap_row_b1</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">6</td><td class="hex">60</td></tr> -<tr><td >reg_ddrc_addrmap_row_b2_11</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">6</td><td class="hex">600</td></tr> -<tr><td >reg_ddrc_addrmap_row_b12</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">6</td><td class="hex">6000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b13</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">6</td><td class="hex">60000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b14</td><td class="hex">23:20</td><td class="hex">f00000</td><td class="hex">f</td><td class="hex">f00000</td></tr> -<tr><td >reg_ddrc_addrmap_row_b15</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">f</td><td class="hex">f000000</td></tr> -<tr><td><b>DRAM_addr_map_row @ 0XF8006044</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>ff66666</b></td></tr></table> -</li> -<li><p>Register : DRAM_ODT_reg @ 0XF8006048</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_local_odt</td><td class="hex">13:12</td><td class="hex">3000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_local_odt</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">3</td><td class="hex">c000</td></tr> -<tr><td >reg_phy_idle_local_odt</td><td class="hex">17:16</td><td class="hex">30000</td><td class="hex">3</td><td class="hex">30000</td></tr> -<tr><td><b>DRAM_ODT_reg @ 0XF8006048</td><td></td><td class="hex"><b>3f000</b></td><td></td><td class="hex"><b>3c000</b></td></tr></table> -</li> -<li><p>Register : phy_cmd_timeout_rddata_cpt @ 0XF8006050</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_cmd_to_data</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_cmd_to_data</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rdc_we_to_re_delay</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">8</td><td class="hex">800</td></tr> -<tr><td >reg_phy_rdc_fifo_rst_disable</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_use_fixed_re</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_phy_rdc_fifo_rst_err_cnt_clr</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dis_phy_ctrl_rstn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_clk_stall_level</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_num_of_dq0</td><td class="hex">27:24</td><td class="hex">f000000</td><td class="hex">7</td><td class="hex">7000000</td></tr> -<tr><td >reg_phy_wrlvl_num_of_dq0</td><td class="hex">31:28</td><td class="hex">f0000000</td><td class="hex">7</td><td class="hex">70000000</td></tr> -<tr><td><b>phy_cmd_timeout_rddata_cpt @ 0XF8006050</td><td></td><td class="hex"><b>ff0f8fff</b></td><td></td><td class="hex"><b>77010800</b></td></tr></table> -</li> -<li><p>Register : DLL_calib @ 0XF8006058</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dis_dll_calib</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DLL_calib @ 0XF8006058</td><td></td><td class="hex"><b>10000</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : ODT_delay_hold @ 0XF800605C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_rd_odt_delay</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">3</td><td class="hex">3</td></tr> -<tr><td >reg_ddrc_wr_odt_delay</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rd_odt_hold</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_wr_odt_hold</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">5</td><td class="hex">5000</td></tr> -<tr><td><b>ODT_delay_hold @ 0XF800605C</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>5003</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg1 @ 0XF8006060</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_pageclose</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_lpr_num_entries</td><td class="hex">6:1</td><td class="hex">7e</td><td class="hex">1f</td><td class="hex">3e</td></tr> -<tr><td >reg_ddrc_auto_pre_en</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_refresh_update_level</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_wc</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_collision_page_opt</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_selfref_en</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ctrl_reg1 @ 0XF8006060</td><td></td><td class="hex"><b>17ff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg2 @ 0XF8006064</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_go2critical_hysteresis</td><td class="hex">12:5</td><td class="hex">1fe0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_go2critical_en</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">1</td><td class="hex">20000</td></tr> -<tr><td><b>ctrl_reg2 @ 0XF8006064</td><td></td><td class="hex"><b>21fe0</b></td><td></td><td class="hex"><b>20000</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg3 @ 0XF8006068</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_wrlvl_ww</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">41</td><td class="hex">41</td></tr> -<tr><td >reg_ddrc_rdlvl_rr</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">41</td><td class="hex">4100</td></tr> -<tr><td >reg_ddrc_dfi_t_wlmrd</td><td class="hex">25:16</td><td class="hex">3ff0000</td><td class="hex">28</td><td class="hex">280000</td></tr> -<tr><td><b>ctrl_reg3 @ 0XF8006068</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>284141</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg4 @ 0XF800606C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >dfi_t_ctrlupd_interval_min_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">10</td><td class="hex">10</td></tr> -<tr><td >dfi_t_ctrlupd_interval_max_x1024</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">16</td><td class="hex">1600</td></tr> -<tr><td><b>ctrl_reg4 @ 0XF800606C</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>1610</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg5 @ 0XF8006078</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dfi_t_ctrl_delay</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_dfi_t_dram_clk_disable</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >reg_ddrc_dfi_t_dram_clk_enable</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >reg_ddrc_t_cksre</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">6</td><td class="hex">6000</td></tr> -<tr><td >reg_ddrc_t_cksrx</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">6</td><td class="hex">60000</td></tr> -<tr><td >reg_ddrc_t_ckesr</td><td class="hex">25:20</td><td class="hex">3f00000</td><td class="hex">4</td><td class="hex">400000</td></tr> -<tr><td><b>ctrl_reg5 @ 0XF8006078</td><td></td><td class="hex"><b>3ffffff</b></td><td></td><td class="hex"><b>466111</b></td></tr></table> -</li> -<li><p>Register : ctrl_reg6 @ 0XF800607C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_t_ckpde</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">2</td><td class="hex">2</td></tr> -<tr><td >reg_ddrc_t_ckpdx</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">2</td><td class="hex">20</td></tr> -<tr><td >reg_ddrc_t_ckdpde</td><td class="hex">11:8</td><td class="hex">f00</td><td class="hex">2</td><td class="hex">200</td></tr> -<tr><td >reg_ddrc_t_ckdpdx</td><td class="hex">15:12</td><td class="hex">f000</td><td class="hex">2</td><td class="hex">2000</td></tr> -<tr><td >reg_ddrc_t_ckcsx</td><td class="hex">19:16</td><td class="hex">f0000</td><td class="hex">3</td><td class="hex">30000</td></tr> -<tr><td><b>ctrl_reg6 @ 0XF800607C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>32222</b></td></tr></table> -</li> -<li><p>Register : CHE_T_ZQ @ 0XF80060A4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dis_auto_zq</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_ddr3</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >reg_ddrc_t_mod</td><td class="hex">11:2</td><td class="hex">ffc</td><td class="hex">200</td><td class="hex">800</td></tr> -<tr><td >reg_ddrc_t_zq_long_nop</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">200</td><td class="hex">200000</td></tr> -<tr><td >reg_ddrc_t_zq_short_nop</td><td class="hex">31:22</td><td class="hex">ffc00000</td><td class="hex">40</td><td class="hex">10000000</td></tr> -<tr><td><b>CHE_T_ZQ @ 0XF80060A4</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>10200802</b></td></tr></table> -</li> -<li><p>Register : CHE_T_ZQ_Short_Interval_Reg @ 0XF80060A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >t_zq_short_interval_x1024</td><td class="hex">19:0</td><td class="hex">fffff</td><td class="hex">c845</td><td class="hex">c845</td></tr> -<tr><td >dram_rstn_x1024</td><td class="hex">27:20</td><td class="hex">ff00000</td><td class="hex">67</td><td class="hex">6700000</td></tr> -<tr><td><b>CHE_T_ZQ_Short_Interval_Reg @ 0XF80060A8</td><td></td><td class="hex"><b>fffffff</b></td><td></td><td class="hex"><b>670c845</b></td></tr></table> -</li> -<li><p>Register : deep_pwrdwn_reg @ 0XF80060AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >deeppowerdown_en</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >deeppowerdown_to_x1024</td><td class="hex">8:1</td><td class="hex">1fe</td><td class="hex">ff</td><td class="hex">1fe</td></tr> -<tr><td><b>deep_pwrdwn_reg @ 0XF80060AC</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>1fe</b></td></tr></table> -</li> -<li><p>Register : reg_2c @ 0XF80060B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >dfi_wrlvl_max_x1024</td><td class="hex">11:0</td><td class="hex">fff</td><td class="hex">fff</td><td class="hex">fff</td></tr> -<tr><td >dfi_rdlvl_max_x1024</td><td class="hex">23:12</td><td class="hex">fff000</td><td class="hex">fff</td><td class="hex">fff000</td></tr> -<tr><td >ddrc_reg_twrlvl_max_error</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ddrc_reg_trdlvl_max_error</td><td class="hex">25:25</td><td class="hex">2000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dfi_wr_level_en</td><td class="hex">26:26</td><td class="hex">4000000</td><td class="hex">1</td><td class="hex">4000000</td></tr> -<tr><td >reg_ddrc_dfi_rd_dqs_gate_level</td><td class="hex">27:27</td><td class="hex">8000000</td><td class="hex">1</td><td class="hex">8000000</td></tr> -<tr><td >reg_ddrc_dfi_rd_data_eye_train</td><td class="hex">28:28</td><td class="hex">10000000</td><td class="hex">1</td><td class="hex">10000000</td></tr> -<tr><td><b>reg_2c @ 0XF80060B0</td><td></td><td class="hex"><b>1fffffff</b></td><td></td><td class="hex"><b>1cffffff</b></td></tr></table> -</li> -<li><p>Register : reg_2d @ 0XF80060B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_skip_ocd</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td><b>reg_2d @ 0XF80060B4</td><td></td><td class="hex"><b>200</b></td><td></td><td class="hex"><b>200</b></td></tr></table> -</li> -<li><p>Register : dfi_timing @ 0XF80060B8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_dfi_t_rddata_en</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td >reg_ddrc_dfi_t_ctrlup_min</td><td class="hex">14:5</td><td class="hex">7fe0</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >reg_ddrc_dfi_t_ctrlup_max</td><td class="hex">24:15</td><td class="hex">1ff8000</td><td class="hex">40</td><td class="hex">200000</td></tr> -<tr><td><b>dfi_timing @ 0XF80060B8</td><td></td><td class="hex"><b>1ffffff</b></td><td></td><td class="hex"><b>200066</b></td></tr></table> -</li> -<h2>RESET ECC ERROR</h2> -<ul> -<p>RESET ECC ERROR</p> -<li><p>Register : CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Clear_Uncorrectable_DRAM_ECC_error</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >Clear_Correctable_DRAM_ECC_error</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td><b>CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</td><td></td><td class="hex"><b>3</b></td><td></td><td class="hex"><b>3</b></td></tr></table> -</li> -</ul> -<li><p>Register : CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Clear_Uncorrectable_DRAM_ECC_error</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Clear_Correctable_DRAM_ECC_error</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_ECC_CONTROL_REG_OFFSET @ 0XF80060C4</td><td></td><td class="hex"><b>3</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_CORR_ECC_LOG_REG_OFFSET @ 0XF80060C8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CORR_ECC_LOG_VALID</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >ECC_CORRECTED_BIT_NUM</td><td class="hex">7:1</td><td class="hex">fe</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_CORR_ECC_LOG_REG_OFFSET @ 0XF80060C8</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_UNCORR_ECC_LOG_REG_OFFSET @ 0XF80060DC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNCORR_ECC_LOG_VALID</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_UNCORR_ECC_LOG_REG_OFFSET @ 0XF80060DC</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : CHE_ECC_STATS_REG_OFFSET @ 0XF80060F0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STAT_NUM_CORR_ERR</td><td class="hex">15:8</td><td class="hex">ff00</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STAT_NUM_UNCORR_ERR</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CHE_ECC_STATS_REG_OFFSET @ 0XF80060F0</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : ECC_scrub @ 0XF80060F4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_ecc_mode</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_scrub</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td><b>ECC_scrub @ 0XF80060F4</td><td></td><td class="hex"><b>f</b></td><td></td><td class="hex"><b>8</b></td></tr></table> -</li> -<li><p>Register : phy_rcvr_enable @ 0XF8006114</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_dif_on</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dif_off</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rcvr_enable @ 0XF8006114</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF8006118</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF8006118</td><td></td><td class="hex"><b>7fffffcf</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF800611C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF800611C</td><td></td><td class="hex"><b>7fffffcf</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF8006120</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF8006120</td><td></td><td class="hex"><b>7fffffcf</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : PHY_Config @ 0XF8006124</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_data_slice_in_use</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_phy_rdlvl_inc_mode</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_inc_mode</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wrlvl_inc_mode</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_shift_dq</td><td class="hex">14:6</td><td class="hex">7fc0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_err_clr</td><td class="hex">23:15</td><td class="hex">ff8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_dq_offset</td><td class="hex">30:24</td><td class="hex">7f000000</td><td class="hex">40</td><td class="hex">40000000</td></tr> -<tr><td><b>PHY_Config @ 0XF8006124</td><td></td><td class="hex"><b>7fffffcf</b></td><td></td><td class="hex"><b>40000001</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF800612C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8f</td><td class="hex">23c00</td></tr> -<tr><td><b>phy_init_ratio @ 0XF800612C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>23c00</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF8006130</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8a</td><td class="hex">22800</td></tr> -<tr><td><b>phy_init_ratio @ 0XF8006130</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>22800</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF8006134</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">8b</td><td class="hex">22c00</td></tr> -<tr><td><b>phy_init_ratio @ 0XF8006134</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>22c00</b></td></tr></table> -</li> -<li><p>Register : phy_init_ratio @ 0XF8006138</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wrlvl_init_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_gatelvl_init_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">92</td><td class="hex">24800</td></tr> -<tr><td><b>phy_init_ratio @ 0XF8006138</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>24800</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF8006140</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF8006140</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF8006144</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF8006144</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF8006148</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF8006148</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_rd_dqs_cfg @ 0XF800614C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_rd_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">35</td><td class="hex">35</td></tr> -<tr><td >reg_phy_rd_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_rd_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_rd_dqs_cfg @ 0XF800614C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>35</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF8006154</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">77</td><td class="hex">77</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF8006154</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>77</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF8006158</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">7c</td><td class="hex">7c</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF8006158</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>7c</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF800615C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">7c</td><td class="hex">7c</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF800615C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>7c</b></td></tr></table> -</li> -<li><p>Register : phy_wr_dqs_cfg @ 0XF8006160</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_dqs_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">75</td><td class="hex">75</td></tr> -<tr><td >reg_phy_wr_dqs_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_dqs_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_wr_dqs_cfg @ 0XF8006160</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>75</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF8006168</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e4</td><td class="hex">e4</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF8006168</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e4</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF800616C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">df</td><td class="hex">df</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF800616C</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>df</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF8006170</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e0</td><td class="hex">e0</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF8006170</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e0</b></td></tr></table> -</li> -<li><p>Register : phy_we_cfg @ 0XF8006174</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_fifo_we_slave_ratio</td><td class="hex">10:0</td><td class="hex">7ff</td><td class="hex">e7</td><td class="hex">e7</td></tr> -<tr><td >reg_phy_fifo_we_in_force</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_fifo_we_in_delay</td><td class="hex">20:12</td><td class="hex">1ff000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>phy_we_cfg @ 0XF8006174</td><td></td><td class="hex"><b>1fffff</b></td><td></td><td class="hex"><b>e7</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF800617C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">b7</td><td class="hex">b7</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF800617C</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>b7</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF8006180</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">bc</td><td class="hex">bc</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF8006180</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>bc</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF8006184</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">bc</td><td class="hex">bc</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF8006184</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>bc</b></td></tr></table> -</li> -<li><p>Register : wr_data_slv @ 0XF8006188</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_data_slave_ratio</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">b5</td><td class="hex">b5</td></tr> -<tr><td >reg_phy_wr_data_slave_force</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_wr_data_slave_delay</td><td class="hex">19:11</td><td class="hex">ff800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>wr_data_slv @ 0XF8006188</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>b5</b></td></tr></table> -</li> -<li><p>Register : reg_64 @ 0XF8006190</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_bl2</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_at_spd_atpg</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_enable</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_force_err</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_bist_mode</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_invert_clkout</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_phy_sel_logic</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_ratio</td><td class="hex">19:10</td><td class="hex">ffc00</td><td class="hex">100</td><td class="hex">40000</td></tr> -<tr><td >reg_phy_ctrl_slave_force</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_delay</td><td class="hex">27:21</td><td class="hex">fe00000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_lpddr</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_cmd_latency</td><td class="hex">30:30</td><td class="hex">40000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_64 @ 0XF8006190</td><td></td><td class="hex"><b>6ffffefe</b></td><td></td><td class="hex"><b>40080</b></td></tr></table> -</li> -<li><p>Register : reg_65 @ 0XF8006194</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_phy_wr_rl_delay</td><td class="hex">4:0</td><td class="hex">1f</td><td class="hex">2</td><td class="hex">2</td></tr> -<tr><td >reg_phy_rd_rl_delay</td><td class="hex">9:5</td><td class="hex">3e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >reg_phy_dll_lock_diff</td><td class="hex">13:10</td><td class="hex">3c00</td><td class="hex">f</td><td class="hex">3c00</td></tr> -<tr><td >reg_phy_use_wr_level</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">1</td><td class="hex">4000</td></tr> -<tr><td >reg_phy_use_rd_dqs_gate_level</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">1</td><td class="hex">8000</td></tr> -<tr><td >reg_phy_use_rd_data_eye_level</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reg_phy_dis_calib_rst</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_phy_ctrl_slave_delay</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>reg_65 @ 0XF8006194</td><td></td><td class="hex"><b>fffff</b></td><td></td><td class="hex"><b>1fc82</b></td></tr></table> -</li> -<li><p>Register : page_mask @ 0XF8006204</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_page_addr_mask</td><td class="hex">31:0</td><td class="hex">ffffffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>page_mask @ 0XF8006204</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF8006208</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF8006208</td><td></td><td class="hex"><b>703ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF800620C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF800620C</td><td></td><td class="hex"><b>703ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF8006210</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF8006210</td><td></td><td class="hex"><b>703ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_wr_port @ 0XF8006214</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_wr_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_wr_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_wr_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_wr_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_wr_port @ 0XF8006214</td><td></td><td class="hex"><b>703ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF8006218</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF8006218</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF800621C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF800621C</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF8006220</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF8006220</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : axi_priority_rd_port @ 0XF8006224</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_arb_pri_rd_portn</td><td class="hex">9:0</td><td class="hex">3ff</td><td class="hex">3ff</td><td class="hex">3ff</td></tr> -<tr><td >reg_arb_disable_aging_rd_portn</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_disable_urgent_rd_portn</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_dis_page_match_rd_portn</td><td class="hex">18:18</td><td class="hex">40000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_arb_set_hpr_rd_portn</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>axi_priority_rd_port @ 0XF8006224</td><td></td><td class="hex"><b>f03ff</b></td><td></td><td class="hex"><b>3ff</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl0 @ 0XF80062A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_lpddr2</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_derate_enable</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_mr4_margin</td><td class="hex">11:4</td><td class="hex">ff0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>lpddr_ctrl0 @ 0XF80062A8</td><td></td><td class="hex"><b>ff5</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl1 @ 0XF80062AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_mr4_read_interval</td><td class="hex">31:0</td><td class="hex">ffffffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>lpddr_ctrl1 @ 0XF80062AC</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl2 @ 0XF80062B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_min_stable_clock_x1</td><td class="hex">3:0</td><td class="hex">f</td><td class="hex">5</td><td class="hex">5</td></tr> -<tr><td >reg_ddrc_idle_after_reset_x32</td><td class="hex">11:4</td><td class="hex">ff0</td><td class="hex">12</td><td class="hex">120</td></tr> -<tr><td >reg_ddrc_t_mrw</td><td class="hex">21:12</td><td class="hex">3ff000</td><td class="hex">5</td><td class="hex">5000</td></tr> -<tr><td><b>lpddr_ctrl2 @ 0XF80062B0</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>5125</b></td></tr></table> -</li> -<li><p>Register : lpddr_ctrl3 @ 0XF80062B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_max_auto_init_x1024</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">a6</td><td class="hex">a6</td></tr> -<tr><td >reg_ddrc_dev_zqinit_x32</td><td class="hex">17:8</td><td class="hex">3ff00</td><td class="hex">12</td><td class="hex">1200</td></tr> -<tr><td><b>lpddr_ctrl3 @ 0XF80062B4</td><td></td><td class="hex"><b>3ffff</b></td><td></td><td class="hex"><b>12a6</b></td></tr></table> -</li> -<h2>POLL ON DCI STATUS</h2> -<ul> -<p>POLL ON DCI STATUS</p> -<li><p>Register : DDRIOB_DCI_STATUS @ 0XF8000B74</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DONE</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>DDRIOB_DCI_STATUS @ 0XF8000B74</td><td></td><td class="hex"><b>2000</b></td><td></td><td class="hex"><b>2000</b></td></tr></table> -</li> -</ul> -<h2>UNLOCK DDR</h2> -<ul> -<p>UNLOCK DDR</p> -<li><p>Register : ddrc_ctrl @ 0XF8006000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reg_ddrc_soft_rstb</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >reg_ddrc_powerdown_en</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_data_bus_width</td><td class="hex">3:2</td><td class="hex">c</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_burst8_refresh</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_rdwr_idle_gap</td><td class="hex">13:7</td><td class="hex">3f80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >reg_ddrc_dis_rd_bypass</td><td class="hex">14:14</td><td class="hex">4000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_act_bypass</td><td class="hex">15:15</td><td class="hex">8000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reg_ddrc_dis_auto_refresh</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>ddrc_ctrl @ 0XF8006000</td><td></td><td class="hex"><b>1ffff</b></td><td></td><td class="hex"><b>81</b></td></tr></table> -</li> -</ul> -<h2>CHECK DDR STATUS</h2> -<ul> -<p>CHECK DDR STATUS</p> -<li><p>Register : mode_sts_reg @ 0XF8006054</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >ddrc_reg_operating_mode</td><td class="hex">2:0</td><td class="hex">7</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>mode_sts_reg @ 0XF8006054</td><td></td><td class="hex"><b>7</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -</ul> -</ul> -<hr/> -<h1><a name="ps7_mio_init_data_3_0">ps7_mio_init_data_3_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>OCM REMAPPING</h2> -<ul> -<p>OCM REMAPPING</p> -<li><p>Register : GPIOB_CTRL @ 0XF8000B00</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >VREF_EN</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >VREF_SEL</td><td class="hex">6:4</td><td class="hex">70</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>GPIOB_CTRL @ 0XF8000B00</td><td></td><td class="hex"><b>71</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DDRIOB SETTINGS</h2> -<ul> -<p>DDRIOB SETTINGS</p> -<li><p>Register : DDRIOB_ADDR0 @ 0XF8000B40</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE_B</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_ADDR0 @ 0XF8000B40</td><td></td><td class="hex"><b>ffe</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_ADDR1 @ 0XF8000B44</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE_B</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_ADDR1 @ 0XF8000B44</td><td></td><td class="hex"><b>ffe</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA0 @ 0XF8000B48</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DCI_UPDATE_B</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCI_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DATA0 @ 0XF8000B48</td><td></td><td class="hex"><b>ffe</b></td><td></td><td class="hex"><b>672</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA1 @ 0XF8000B4C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >DCI_UPDATE_B</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCI_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DATA1 @ 0XF8000B4C</td><td></td><td class="hex"><b>ffe</b></td><td></td><td class="hex"><b>672</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF0 @ 0XF8000B50</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">2</td><td class="hex">4</td></tr> -<tr><td >DCI_UPDATE_B</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCI_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DIFF0 @ 0XF8000B50</td><td></td><td class="hex"><b>ffe</b></td><td></td><td class="hex"><b>674</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF1 @ 0XF8000B54</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">2</td><td class="hex">4</td></tr> -<tr><td >DCI_UPDATE_B</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >DCI_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DIFF1 @ 0XF8000B54</td><td></td><td class="hex"><b>ffe</b></td><td></td><td class="hex"><b>674</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_CLOCK @ 0XF8000B58</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >INP_TYPE</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_UPDATE_B</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_EN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DCI_TYPE</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >OUTPUT_EN</td><td class="hex">10:9</td><td class="hex">600</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP_EN</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_CLOCK @ 0XF8000B58</td><td></td><td class="hex"><b>ffe</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DDR_CTRL @ 0XF8000B6C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >VREF_INT_EN</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VREF_SEL</td><td class="hex">4:1</td><td class="hex">1e</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >VREF_EXT_EN</td><td class="hex">6:5</td><td class="hex">60</td><td class="hex">3</td><td class="hex">60</td></tr> -<tr><td >REFIO_EN</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td><b>DDRIOB_DDR_CTRL @ 0XF8000B6C</td><td></td><td class="hex"><b>27f</b></td><td></td><td class="hex"><b>260</b></td></tr></table> -</li> -<h2>ASSERT RESET</h2> -<ul> -<p>ASSERT RESET</p> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>1</b></td></tr></table> -</li> -</ul> -<h2>DEASSERT RESET</h2> -<ul> -<p>DEASSERT RESET</p> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>1</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<li><p>Register : DDRIOB_DCI_CTRL @ 0XF8000B70</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >RESET</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >ENABLE</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >NREF_OPT1</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NREF_OPT2</td><td class="hex">10:8</td><td class="hex">700</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NREF_OPT4</td><td class="hex">13:11</td><td class="hex">3800</td><td class="hex">1</td><td class="hex">800</td></tr> -<tr><td >PREF_OPT2</td><td class="hex">19:17</td><td class="hex">e0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >UPDATE_CONTROL</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>DDRIOB_DCI_CTRL @ 0XF8000B70</td><td></td><td class="hex"><b>1e3fc3</b></td><td></td><td class="hex"><b>803</b></td></tr></table> -</li> -</ul> -<h2>MIO PROGRAMMING</h2> -<ul> -<p>MIO PROGRAMMING</p> -<li><p>Register : MIO_PIN_00 @ 0XF8000700</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_00 @ 0XF8000700</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_01 @ 0XF8000704</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_01 @ 0XF8000704</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_02 @ 0XF8000708</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_02 @ 0XF8000708</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_03 @ 0XF800070C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_03 @ 0XF800070C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_04 @ 0XF8000710</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_04 @ 0XF8000710</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_05 @ 0XF8000714</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_05 @ 0XF8000714</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_06 @ 0XF8000718</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_06 @ 0XF8000718</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_07 @ 0XF800071C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_07 @ 0XF800071C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_08 @ 0XF8000720</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_08 @ 0XF8000720</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>702</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_09 @ 0XF8000724</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_09 @ 0XF8000724</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_10 @ 0XF8000728</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_10 @ 0XF8000728</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>1640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_11 @ 0XF800072C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_11 @ 0XF800072C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>1640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_12 @ 0XF8000730</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_12 @ 0XF8000730</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_13 @ 0XF8000734</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">2</td><td class="hex">40</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_13 @ 0XF8000734</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>640</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_14 @ 0XF8000738</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_14 @ 0XF8000738</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_15 @ 0XF800073C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">3</td><td class="hex">600</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_15 @ 0XF800073C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>600</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_16 @ 0XF8000740</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_16 @ 0XF8000740</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_17 @ 0XF8000744</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_17 @ 0XF8000744</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_18 @ 0XF8000748</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_18 @ 0XF8000748</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_19 @ 0XF800074C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_19 @ 0XF800074C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_20 @ 0XF8000750</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_20 @ 0XF8000750</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_21 @ 0XF8000754</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td><b>MIO_PIN_21 @ 0XF8000754</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2902</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_22 @ 0XF8000758</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_22 @ 0XF8000758</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_23 @ 0XF800075C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_23 @ 0XF800075C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_24 @ 0XF8000760</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_24 @ 0XF8000760</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_25 @ 0XF8000764</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_25 @ 0XF8000764</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_26 @ 0XF8000768</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_26 @ 0XF8000768</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_27 @ 0XF800076C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">4</td><td class="hex">800</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_27 @ 0XF800076C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>903</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_28 @ 0XF8000770</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_28 @ 0XF8000770</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_29 @ 0XF8000774</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_29 @ 0XF8000774</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_30 @ 0XF8000778</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_30 @ 0XF8000778</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_31 @ 0XF800077C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_31 @ 0XF800077C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_32 @ 0XF8000780</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_32 @ 0XF8000780</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_33 @ 0XF8000784</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_33 @ 0XF8000784</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_34 @ 0XF8000788</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_34 @ 0XF8000788</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_35 @ 0XF800078C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_35 @ 0XF800078C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_36 @ 0XF8000790</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_36 @ 0XF8000790</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>305</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_37 @ 0XF8000794</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_37 @ 0XF8000794</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_38 @ 0XF8000798</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_38 @ 0XF8000798</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_39 @ 0XF800079C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_39 @ 0XF800079C</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>304</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_40 @ 0XF80007A0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_40 @ 0XF80007A0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_41 @ 0XF80007A4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_41 @ 0XF80007A4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_42 @ 0XF80007A8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_42 @ 0XF80007A8</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_43 @ 0XF80007AC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_43 @ 0XF80007AC</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_44 @ 0XF80007B0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_44 @ 0XF80007B0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_45 @ 0XF80007B4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_45 @ 0XF80007B4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>380</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_46 @ 0XF80007B8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_46 @ 0XF80007B8</td><td></td><td class="hex"><b>3f01</b></td><td></td><td class="hex"><b>200</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_47 @ 0XF80007BC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_47 @ 0XF80007BC</td><td></td><td class="hex"><b>3f01</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_48 @ 0XF80007C0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_48 @ 0XF80007C0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2e0</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_49 @ 0XF80007C4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">7</td><td class="hex">e0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_49 @ 0XF80007C4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>2e1</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_50 @ 0XF80007C8</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_50 @ 0XF80007C8</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_51 @ 0XF80007CC</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_51 @ 0XF80007CC</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>201</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_52 @ 0XF80007D0</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_52 @ 0XF80007D0</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>280</b></td></tr></table> -</li> -<li><p>Register : MIO_PIN_53 @ 0XF80007D4</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >TRI_ENABLE</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L0_SEL</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L1_SEL</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L2_SEL</td><td class="hex">4:3</td><td class="hex">18</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >L3_SEL</td><td class="hex">7:5</td><td class="hex">e0</td><td class="hex">4</td><td class="hex">80</td></tr> -<tr><td >Speed</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >IO_Type</td><td class="hex">11:9</td><td class="hex">e00</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >PULLUP</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >DisableRcvr</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MIO_PIN_53 @ 0XF80007D4</td><td></td><td class="hex"><b>3fff</b></td><td></td><td class="hex"><b>280</b></td></tr></table> -</li> -<li><p>Register : SD0_WP_CD_SEL @ 0XF8000830</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >SDIO0_CD_SEL</td><td class="hex">21:16</td><td class="hex">3f0000</td><td class="hex">2f</td><td class="hex">2f0000</td></tr> -<tr><td><b>SD0_WP_CD_SEL @ 0XF8000830</td><td></td><td class="hex"><b>3f0000</b></td><td></td><td class="hex"><b>2f0000</b></td></tr></table> -</li> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -<h1><a name="ps7_peripherals_init_data_3_0">ps7_peripherals_init_data_3_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>DDR TERM/IBUF_DISABLE_MODE SETTINGS</h2> -<ul> -<p>DDR TERM/IBUF_DISABLE_MODE SETTINGS</p> -<li><p>Register : DDRIOB_DATA0 @ 0XF8000B48</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DATA0 @ 0XF8000B48</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DATA1 @ 0XF8000B4C</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DATA1 @ 0XF8000B4C</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF0 @ 0XF8000B50</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DIFF0 @ 0XF8000B50</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -<li><p>Register : DDRIOB_DIFF1 @ 0XF8000B54</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >IBUF_DISABLE_MODE</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">1</td><td class="hex">80</td></tr> -<tr><td >TERM_DISABLE_MODE</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td><b>DDRIOB_DIFF1 @ 0XF8000B54</td><td></td><td class="hex"><b>180</b></td><td></td><td class="hex"><b>180</b></td></tr></table> -</li> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -<h2>SRAM/NOR SET OPMODE</h2> -<ul> -<p>SRAM/NOR SET OPMODE</p> -</ul> -<h2>UART REGISTERS</h2> -<ul> -<p>UART REGISTERS</p> -<li><p>Register : Baud_rate_divider_reg0 @ 0XE0001034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >BDIV</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td><b>Baud_rate_divider_reg0 @ 0XE0001034</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>6</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_gen_reg0 @ 0XE0001018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CD</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">3e</td><td class="hex">3e</td></tr> -<tr><td><b>Baud_rate_gen_reg0 @ 0XE0001018</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : Control_reg0 @ 0XE0001000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STPBRK</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STTBRK</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RSTTO</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXDIS</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXEN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >RXDIS</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RXEN</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >TXRES</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >RXRES</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>Control_reg0 @ 0XE0001000</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>17</b></td></tr></table> -</li> -<li><p>Register : mode_reg0 @ 0XE0001004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CHMODE</td><td class="hex">9:8</td><td class="hex">300</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NBSTOP</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PAR</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">4</td><td class="hex">20</td></tr> -<tr><td >CHRL</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLKS</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>mode_reg0 @ 0XE0001004</td><td></td><td class="hex"><b>3ff</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_divider_reg0 @ 0XE0000034</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >BDIV</td><td class="hex">7:0</td><td class="hex">ff</td><td class="hex">6</td><td class="hex">6</td></tr> -<tr><td><b>Baud_rate_divider_reg0 @ 0XE0000034</td><td></td><td class="hex"><b>ff</b></td><td></td><td class="hex"><b>6</b></td></tr></table> -</li> -<li><p>Register : Baud_rate_gen_reg0 @ 0XE0000018</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CD</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">3e</td><td class="hex">3e</td></tr> -<tr><td><b>Baud_rate_gen_reg0 @ 0XE0000018</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>3e</b></td></tr></table> -</li> -<li><p>Register : Control_reg0 @ 0XE0000000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >STPBRK</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >STTBRK</td><td class="hex">7:7</td><td class="hex">80</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RSTTO</td><td class="hex">6:6</td><td class="hex">40</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXDIS</td><td class="hex">5:5</td><td class="hex">20</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >TXEN</td><td class="hex">4:4</td><td class="hex">10</td><td class="hex">1</td><td class="hex">10</td></tr> -<tr><td >RXDIS</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >RXEN</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >TXRES</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >RXRES</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>Control_reg0 @ 0XE0000000</td><td></td><td class="hex"><b>1ff</b></td><td></td><td class="hex"><b>17</b></td></tr></table> -</li> -<li><p>Register : mode_reg0 @ 0XE0000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >CHMODE</td><td class="hex">9:8</td><td class="hex">300</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >NBSTOP</td><td class="hex">7:6</td><td class="hex">c0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >PAR</td><td class="hex">5:3</td><td class="hex">38</td><td class="hex">4</td><td class="hex">20</td></tr> -<tr><td >CHRL</td><td class="hex">2:1</td><td class="hex">6</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >CLKS</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>mode_reg0 @ 0XE0000004</td><td></td><td class="hex"><b>3ff</b></td><td></td><td class="hex"><b>20</b></td></tr></table> -</li> -</ul> -<h2>QSPI REGISTERS</h2> -<ul> -<p>QSPI REGISTERS</p> -<li><p>Register : Config_reg @ 0XE000D000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >Holdb_dr</td><td class="hex">19:19</td><td class="hex">80000</td><td class="hex">1</td><td class="hex">80000</td></tr> -<tr><td><b>Config_reg @ 0XE000D000</td><td></td><td class="hex"><b>80000</b></td><td></td><td class="hex"><b>80000</b></td></tr></table> -</li> -</ul> -<h2>PL POWER ON RESET REGISTERS</h2> -<ul> -<p>PL POWER ON RESET REGISTERS</p> -<li><p>Register : CTRL @ 0XF8007000</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >PCFG_POR_CNT_4K</td><td class="hex">29:29</td><td class="hex">20000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>CTRL @ 0XF8007000</td><td></td><td class="hex"><b>20000000</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>SMC TIMING CALCULATION REGISTER UPDATE</h2> -<ul> -<p>SMC TIMING CALCULATION REGISTER UPDATE</p> -<h2>NAND SET CYCLE</h2> -<ul> -<p>NAND SET CYCLE</p> -</ul> -<h2>OPMODE</h2> -<ul> -<p>OPMODE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>SRAM/NOR CS0 SET CYCLE</h2> -<ul> -<p>SRAM/NOR CS0 SET CYCLE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>NOR CS0 BASE ADDRESS</h2> -<ul> -<p>NOR CS0 BASE ADDRESS</p> -</ul> -<h2>SRAM/NOR CS1 SET CYCLE</h2> -<ul> -<p>SRAM/NOR CS1 SET CYCLE</p> -</ul> -<h2>DIRECT COMMAND</h2> -<ul> -<p>DIRECT COMMAND</p> -</ul> -<h2>NOR CS1 BASE ADDRESS</h2> -<ul> -<p>NOR CS1 BASE ADDRESS</p> -</ul> -<h2>USB RESET</h2> -<ul> -<p>USB RESET</p> -<h2>DIR MODE BANK 0</h2> -<ul> -<p>DIR MODE BANK 0</p> -</ul> -<h2>DIR MODE BANK 1</h2> -<ul> -<p>DIR MODE BANK 1</p> -<li><p>Register : DIRM_1 @ 0XE000A244</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >DIRECTION_1</td><td class="hex">21:0</td><td class="hex">3fffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>DIRM_1 @ 0XE000A244</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE BANK 0</h2> -<ul> -<p>OUTPUT ENABLE BANK 0</p> -</ul> -<h2>OUTPUT ENABLE BANK 1</h2> -<ul> -<p>OUTPUT ENABLE BANK 1</p> -<li><p>Register : OEN_1 @ 0XE000A248</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >OP_ENABLE_1</td><td class="hex">21:0</td><td class="hex">3fffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>OEN_1 @ 0XE000A248</td><td></td><td class="hex"><b>3fffff</b></td><td></td><td class="hex"><b>4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff0000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -<li><p>Register : MASK_DATA_1_LSW @ 0XE000A008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >MASK_1_LSW</td><td class="hex">31:16</td><td class="hex">ffff0000</td><td class="hex">bfff</td><td class="hex">bfff0000</td></tr> -<tr><td >DATA_1_LSW</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">4000</td><td class="hex">4000</td></tr> -<tr><td><b>MASK_DATA_1_LSW @ 0XE000A008</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>bfff4000</b></td></tr></table> -</li> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -<h2>ENET RESET</h2> -<ul> -<p>ENET RESET</p> -<h2>DIR MODE BANK 0</h2> -<ul> -<p>DIR MODE BANK 0</p> -</ul> -<h2>DIR MODE BANK 1</h2> -<ul> -<p>DIR MODE BANK 1</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE BANK 0</h2> -<ul> -<p>OUTPUT ENABLE BANK 0</p> -</ul> -<h2>OUTPUT ENABLE BANK 1</h2> -<ul> -<p>OUTPUT ENABLE BANK 1</p> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -<h2>I2C RESET</h2> -<ul> -<p>I2C RESET</p> -<h2>DIR MODE GPIO BANK0</h2> -<ul> -<p>DIR MODE GPIO BANK0</p> -</ul> -<h2>DIR MODE GPIO BANK1</h2> -<ul> -<p>DIR MODE GPIO BANK1</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -<h2>OUTPUT ENABLE</h2> -<ul> -<p>OUTPUT ENABLE</p> -</ul> -<h2>OUTPUT ENABLE</h2> -<ul> -<p>OUTPUT ENABLE</p> -</ul> -<h2>MASK_DATA_0_LSW LOW BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW LOW BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW LOW BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW LOW BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW LOW BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW LOW BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW LOW BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW LOW BANK [53:48]</p> -</ul> -<h2>MASK_DATA_0_LSW HIGH BANK [15:0]</h2> -<ul> -<p>MASK_DATA_0_LSW HIGH BANK [15:0]</p> -</ul> -<h2>MASK_DATA_0_MSW HIGH BANK [31:16]</h2> -<ul> -<p>MASK_DATA_0_MSW HIGH BANK [31:16]</p> -</ul> -<h2>MASK_DATA_1_LSW HIGH BANK [47:32]</h2> -<ul> -<p>MASK_DATA_1_LSW HIGH BANK [47:32]</p> -</ul> -<h2>MASK_DATA_1_MSW HIGH BANK [53:48]</h2> -<ul> -<p>MASK_DATA_1_MSW HIGH BANK [53:48]</p> -</ul> -</ul> -</ul> -</ul> -<hr/> -<h1><a name="ps7_post_config_3_0">ps7_post_config_3_0</a></h1> -<ul> -<h2>SLCR SETTINGS</h2> -<ul> -<p>SLCR SETTINGS</p> -<li><p>Register : SLCR_UNLOCK @ 0XF8000008</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >UNLOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">df0d</td><td class="hex">df0d</td></tr> -<tr><td><b>SLCR_UNLOCK @ 0XF8000008</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>df0d</b></td></tr></table> -</li> -</ul> -<h2>ENABLING LEVEL SHIFTER</h2> -<ul> -<p>ENABLING LEVEL SHIFTER</p> -<li><p>Register : LVL_SHFTR_EN @ 0XF8000900</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >USER_LVL_INP_EN_0</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >USER_LVL_OUT_EN_0</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >USER_LVL_INP_EN_1</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >USER_LVL_OUT_EN_1</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>LVL_SHFTR_EN @ 0XF8000900</td><td></td><td class="hex"><b>f</b></td><td></td><td class="hex"><b>f</b></td></tr></table> -</li> -</ul> -<h2>FPGA RESETS TO 1</h2> -<ul> -<p>FPGA RESETS TO 1</p> -<li><p>Register : FPGA_RST_CTRL @ 0XF8000240</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reserved_3</td><td class="hex">31:25</td><td class="hex">fe000000</td><td class="hex">7f</td><td class="hex">fe000000</td></tr> -<tr><td >reserved_FPGA_ACP_RST</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">1</td><td class="hex">1000000</td></tr> -<tr><td >reserved_FPGA_AXDS3_RST</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">1</td><td class="hex">800000</td></tr> -<tr><td >reserved_FPGA_AXDS2_RST</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">1</td><td class="hex">400000</td></tr> -<tr><td >reserved_FPGA_AXDS1_RST</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">1</td><td class="hex">200000</td></tr> -<tr><td >reserved_FPGA_AXDS0_RST</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">1</td><td class="hex">100000</td></tr> -<tr><td >reserved_2</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">3</td><td class="hex">c0000</td></tr> -<tr><td >reserved_FSSW1_FPGA_RST</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">1</td><td class="hex">20000</td></tr> -<tr><td >reserved_FSSW0_FPGA_RST</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">1</td><td class="hex">10000</td></tr> -<tr><td >reserved_1</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">3</td><td class="hex">c000</td></tr> -<tr><td >reserved_FPGA_FMSW1_RST</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">1</td><td class="hex">2000</td></tr> -<tr><td >reserved_FPGA_FMSW0_RST</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">1</td><td class="hex">1000</td></tr> -<tr><td >reserved_FPGA_DMA3_RST</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">1</td><td class="hex">800</td></tr> -<tr><td >reserved_FPGA_DMA2_RST</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">1</td><td class="hex">400</td></tr> -<tr><td >reserved_FPGA_DMA1_RST</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">1</td><td class="hex">200</td></tr> -<tr><td >reserved_FPGA_DMA0_RST</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">1</td><td class="hex">100</td></tr> -<tr><td >reserved</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">f</td><td class="hex">f0</td></tr> -<tr><td >FPGA3_OUT_RST</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">1</td><td class="hex">8</td></tr> -<tr><td >FPGA2_OUT_RST</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">1</td><td class="hex">4</td></tr> -<tr><td >FPGA1_OUT_RST</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">1</td><td class="hex">2</td></tr> -<tr><td >FPGA0_OUT_RST</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">1</td><td class="hex">1</td></tr> -<tr><td><b>FPGA_RST_CTRL @ 0XF8000240</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>ffffffff</b></td></tr></table> -</li> -</ul> -<h2>FPGA RESETS TO 0</h2> -<ul> -<p>FPGA RESETS TO 0</p> -<li><p>Register : FPGA_RST_CTRL @ 0XF8000240</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >reserved_3</td><td class="hex">31:25</td><td class="hex">fe000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_ACP_RST</td><td class="hex">24:24</td><td class="hex">1000000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_AXDS3_RST</td><td class="hex">23:23</td><td class="hex">800000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_AXDS2_RST</td><td class="hex">22:22</td><td class="hex">400000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_AXDS1_RST</td><td class="hex">21:21</td><td class="hex">200000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_AXDS0_RST</td><td class="hex">20:20</td><td class="hex">100000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_2</td><td class="hex">19:18</td><td class="hex">c0000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FSSW1_FPGA_RST</td><td class="hex">17:17</td><td class="hex">20000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FSSW0_FPGA_RST</td><td class="hex">16:16</td><td class="hex">10000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_1</td><td class="hex">15:14</td><td class="hex">c000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_FMSW1_RST</td><td class="hex">13:13</td><td class="hex">2000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_FMSW0_RST</td><td class="hex">12:12</td><td class="hex">1000</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_DMA3_RST</td><td class="hex">11:11</td><td class="hex">800</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_DMA2_RST</td><td class="hex">10:10</td><td class="hex">400</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_DMA1_RST</td><td class="hex">9:9</td><td class="hex">200</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved_FPGA_DMA0_RST</td><td class="hex">8:8</td><td class="hex">100</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >reserved</td><td class="hex">7:4</td><td class="hex">f0</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA3_OUT_RST</td><td class="hex">3:3</td><td class="hex">8</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA2_OUT_RST</td><td class="hex">2:2</td><td class="hex">4</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA1_OUT_RST</td><td class="hex">1:1</td><td class="hex">2</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td >FPGA0_OUT_RST</td><td class="hex">0:0</td><td class="hex">1</td><td class="hex">0</td><td class="hex">0</td></tr> -<tr><td><b>FPGA_RST_CTRL @ 0XF8000240</td><td></td><td class="hex"><b>ffffffff</b></td><td></td><td class="hex"><b>0</b></td></tr></table> -</li> -</ul> -<h2>AFI REGISTERS</h2> -<ul> -<p>AFI REGISTERS</p> -<h2>AFI0 REGISTERS</h2> -<ul> -<p>AFI0 REGISTERS</p> -</ul> -<h2>AFI1 REGISTERS</h2> -<ul> -<p>AFI1 REGISTERS</p> -</ul> -<h2>AFI2 REGISTERS</h2> -<ul> -<p>AFI2 REGISTERS</p> -</ul> -<h2>AFI3 REGISTERS</h2> -<ul> -<p>AFI3 REGISTERS</p> -</ul> -</ul> -<h2>LOCK IT BACK</h2> -<ul> -<p>LOCK IT BACK</p> -<li><p>Register : SLCR_LOCK @ 0XF8000004</p> -<table border="1"> -<tr><thead><th>Bitfield</th><th>Bits</th><th>Mask</th><th>Value</th><th>Shifted Value</th></thead></tr><tbody> -<tr><td >LOCK_KEY</td><td class="hex">15:0</td><td class="hex">ffff</td><td class="hex">767b</td><td class="hex">767b</td></tr> -<tr><td><b>SLCR_LOCK @ 0XF8000004</td><td></td><td class="hex"><b>ffff</b></td><td></td><td class="hex"><b>767b</b></td></tr></table> -</li> -</ul> -</ul> -<hr/> -</body> -</html> diff --git a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.tcl b/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.tcl deleted file mode 100644 index 496281373eb5f05c73c312ec0cf9f1a442b20273..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/zybo_fsbl/src/ps7_init.tcl +++ /dev/null @@ -1,762 +0,0 @@ -proc ps7_pll_init_data_1_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000110 0x003FFFF0 0x001772C0 - mask_write 0XF8000100 0x0007F000 0x0001A000 - mask_write 0XF8000100 0x00000010 0x00000010 - mask_write 0XF8000100 0x00000001 0x00000001 - mask_write 0XF8000100 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000001 - mask_write 0XF8000100 0x00000010 0x00000000 - mask_write 0XF8000120 0x1F003F30 0x1F000200 - mask_write 0XF8000114 0x003FFFF0 0x001DB2C0 - mask_write 0XF8000104 0x0007F000 0x00015000 - mask_write 0XF8000104 0x00000010 0x00000010 - mask_write 0XF8000104 0x00000001 0x00000001 - mask_write 0XF8000104 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000002 - mask_write 0XF8000104 0x00000010 0x00000000 - mask_write 0XF8000124 0xFFF00003 0x0C200003 - mask_write 0XF8000118 0x003FFFF0 0x001F42C0 - mask_write 0XF8000108 0x0007F000 0x00014000 - mask_write 0XF8000108 0x00000010 0x00000010 - mask_write 0XF8000108 0x00000001 0x00000001 - mask_write 0XF8000108 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000004 - mask_write 0XF8000108 0x00000010 0x00000000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_clock_init_data_1_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000128 0x03F03F01 0x00203401 - mask_write 0XF8000138 0x00000011 0x00000001 - mask_write 0XF8000140 0x03F03F71 0x00100801 - mask_write 0XF800014C 0x00003F31 0x00000501 - mask_write 0XF8000150 0x00003F33 0x00001401 - mask_write 0XF8000154 0x00003F33 0x00001403 - mask_write 0XF8000168 0x00003F31 0x00000501 - mask_write 0XF8000170 0x03F03F30 0x00100A00 - mask_write 0XF8000180 0x03F03F30 0x00100630 - mask_write 0XF8000190 0x03F03F30 0x00203520 - mask_write 0XF80001A0 0x03F03F30 0x00100A00 - mask_write 0XF80001C4 0x00000001 0x00000001 - mask_write 0XF800012C 0x01FFCCCD 0x01FC044D - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_ddr_init_data_1_0 {} { - mask_write 0XF8006000 0x0001FFFF 0x00000080 - mask_write 0XF8006004 0x1FFFFFFF 0x0008107F - mask_write 0XF8006008 0x03FFFFFF 0x03C0780F - mask_write 0XF800600C 0x03FFFFFF 0x02001001 - mask_write 0XF8006010 0x03FFFFFF 0x00014001 - mask_write 0XF8006014 0x001FFFFF 0x0004151A - mask_write 0XF8006018 0xF7FFFFFF 0x44E354D2 - mask_write 0XF800601C 0xFFFFFFFF 0x720238E5 - mask_write 0XF8006020 0xFFFFFFFC 0x272872D0 - mask_write 0XF8006024 0x0FFFFFFF 0x0000003C - mask_write 0XF8006028 0x00003FFF 0x00002007 - mask_write 0XF800602C 0xFFFFFFFF 0x00000008 - mask_write 0XF8006030 0xFFFFFFFF 0x00040930 - mask_write 0XF8006034 0x13FF3FFF 0x00011014 - mask_write 0XF8006038 0x00001FC3 0x00000000 - mask_write 0XF800603C 0x000FFFFF 0x00000777 - mask_write 0XF8006040 0xFFFFFFFF 0xFFF00000 - mask_write 0XF8006044 0x0FFFFFFF 0x0FF66666 - mask_write 0XF8006048 0x3FFFFFFF 0x0003C248 - mask_write 0XF8006050 0xFF0F8FFF 0x77010800 - mask_write 0XF8006058 0x0001FFFF 0x00000101 - mask_write 0XF800605C 0x0000FFFF 0x00005003 - mask_write 0XF8006060 0x000017FF 0x0000003E - mask_write 0XF8006064 0x00021FE0 0x00020000 - mask_write 0XF8006068 0x03FFFFFF 0x00284141 - mask_write 0XF800606C 0x0000FFFF 0x00001610 - mask_write 0XF80060A0 0x00FFFFFF 0x00008000 - mask_write 0XF80060A4 0xFFFFFFFF 0x10200802 - mask_write 0XF80060A8 0x0FFFFFFF 0x0670C845 - mask_write 0XF80060AC 0x000001FF 0x000001FE - mask_write 0XF80060B0 0x1FFFFFFF 0x1CFFFFFF - mask_write 0XF80060B4 0x000007FF 0x00000200 - mask_write 0XF80060B8 0x01FFFFFF 0x00200066 - mask_write 0XF80060C4 0x00000003 0x00000003 - mask_write 0XF80060C4 0x00000003 0x00000000 - mask_write 0XF80060C8 0x000000FF 0x00000000 - mask_write 0XF80060DC 0x00000001 0x00000000 - mask_write 0XF80060F0 0x0000FFFF 0x00000000 - mask_write 0XF80060F4 0x0000000F 0x00000008 - mask_write 0XF8006114 0x000000FF 0x00000000 - mask_write 0XF8006118 0x7FFFFFFF 0x40000001 - mask_write 0XF800611C 0x7FFFFFFF 0x40000001 - mask_write 0XF8006120 0x7FFFFFFF 0x40000001 - mask_write 0XF8006124 0x7FFFFFFF 0x40000001 - mask_write 0XF800612C 0x000FFFFF 0x00023C00 - mask_write 0XF8006130 0x000FFFFF 0x00022800 - mask_write 0XF8006134 0x000FFFFF 0x00022C00 - mask_write 0XF8006138 0x000FFFFF 0x00024800 - mask_write 0XF8006140 0x000FFFFF 0x00000035 - mask_write 0XF8006144 0x000FFFFF 0x00000035 - mask_write 0XF8006148 0x000FFFFF 0x00000035 - mask_write 0XF800614C 0x000FFFFF 0x00000035 - mask_write 0XF8006154 0x000FFFFF 0x00000077 - mask_write 0XF8006158 0x000FFFFF 0x0000007C - mask_write 0XF800615C 0x000FFFFF 0x0000007C - mask_write 0XF8006160 0x000FFFFF 0x00000075 - mask_write 0XF8006168 0x001FFFFF 0x000000E4 - mask_write 0XF800616C 0x001FFFFF 0x000000DF - mask_write 0XF8006170 0x001FFFFF 0x000000E0 - mask_write 0XF8006174 0x001FFFFF 0x000000E7 - mask_write 0XF800617C 0x000FFFFF 0x000000B7 - mask_write 0XF8006180 0x000FFFFF 0x000000BC - mask_write 0XF8006184 0x000FFFFF 0x000000BC - mask_write 0XF8006188 0x000FFFFF 0x000000B5 - mask_write 0XF8006190 0xFFFFFFFF 0x10040080 - mask_write 0XF8006194 0x000FFFFF 0x0001FC82 - mask_write 0XF8006204 0xFFFFFFFF 0x00000000 - mask_write 0XF8006208 0x000F03FF 0x000803FF - mask_write 0XF800620C 0x000F03FF 0x000803FF - mask_write 0XF8006210 0x000F03FF 0x000803FF - mask_write 0XF8006214 0x000F03FF 0x000803FF - mask_write 0XF8006218 0x000F03FF 0x000003FF - mask_write 0XF800621C 0x000F03FF 0x000003FF - mask_write 0XF8006220 0x000F03FF 0x000003FF - mask_write 0XF8006224 0x000F03FF 0x000003FF - mask_write 0XF80062A8 0x00000FF7 0x00000000 - mask_write 0XF80062AC 0xFFFFFFFF 0x00000000 - mask_write 0XF80062B0 0x003FFFFF 0x00005125 - mask_write 0XF80062B4 0x0003FFFF 0x000012A6 - mask_poll 0XF8000B74 0x00002000 - mask_write 0XF8006000 0x0001FFFF 0x00000081 - mask_poll 0XF8006054 0x00000007 -} -proc ps7_mio_init_data_1_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000B00 0x00000303 0x00000001 - mask_write 0XF8000B40 0x00000FFF 0x00000600 - mask_write 0XF8000B44 0x00000FFF 0x00000600 - mask_write 0XF8000B48 0x00000FFF 0x00000672 - mask_write 0XF8000B4C 0x00000FFF 0x00000672 - mask_write 0XF8000B50 0x00000FFF 0x00000674 - mask_write 0XF8000B54 0x00000FFF 0x00000674 - mask_write 0XF8000B58 0x00000FFF 0x00000600 - mask_write 0XF8000B5C 0xFFFFFFFF 0x00D6861C - mask_write 0XF8000B60 0xFFFFFFFF 0x00F9861C - mask_write 0XF8000B64 0xFFFFFFFF 0x00F9861C - mask_write 0XF8000B68 0xFFFFFFFF 0x00D6861C - mask_write 0XF8000B6C 0x000073FF 0x00000260 - mask_write 0XF8000B70 0x00000021 0x00000021 - mask_write 0XF8000B70 0x00000021 0x00000020 - mask_write 0XF8000B70 0x07FFFFFF 0x00000823 - mask_write 0XF8000700 0x00003FFF 0x00000600 - mask_write 0XF8000704 0x00003FFF 0x00000702 - mask_write 0XF8000708 0x00003FFF 0x00000702 - mask_write 0XF800070C 0x00003FFF 0x00000702 - mask_write 0XF8000710 0x00003FFF 0x00000702 - mask_write 0XF8000714 0x00003FFF 0x00000702 - mask_write 0XF8000718 0x00003FFF 0x00000702 - mask_write 0XF800071C 0x00003FFF 0x00000600 - mask_write 0XF8000720 0x00003FFF 0x00000702 - mask_write 0XF8000724 0x00003FFF 0x00000600 - mask_write 0XF8000728 0x00003FFF 0x00001640 - mask_write 0XF800072C 0x00003FFF 0x00001640 - mask_write 0XF8000730 0x00003FFF 0x00000640 - mask_write 0XF8000734 0x00003FFF 0x00000640 - mask_write 0XF8000738 0x00003FFF 0x00000600 - mask_write 0XF800073C 0x00003FFF 0x00000600 - mask_write 0XF8000740 0x00003FFF 0x00002902 - mask_write 0XF8000744 0x00003FFF 0x00002902 - mask_write 0XF8000748 0x00003FFF 0x00002902 - mask_write 0XF800074C 0x00003FFF 0x00002902 - mask_write 0XF8000750 0x00003FFF 0x00002902 - mask_write 0XF8000754 0x00003FFF 0x00002902 - mask_write 0XF8000758 0x00003FFF 0x00000903 - mask_write 0XF800075C 0x00003FFF 0x00000903 - mask_write 0XF8000760 0x00003FFF 0x00000903 - mask_write 0XF8000764 0x00003FFF 0x00000903 - mask_write 0XF8000768 0x00003FFF 0x00000903 - mask_write 0XF800076C 0x00003FFF 0x00000903 - mask_write 0XF8000770 0x00003FFF 0x00000304 - mask_write 0XF8000774 0x00003FFF 0x00000305 - mask_write 0XF8000778 0x00003FFF 0x00000304 - mask_write 0XF800077C 0x00003FFF 0x00000305 - mask_write 0XF8000780 0x00003FFF 0x00000304 - mask_write 0XF8000784 0x00003FFF 0x00000304 - mask_write 0XF8000788 0x00003FFF 0x00000304 - mask_write 0XF800078C 0x00003FFF 0x00000304 - mask_write 0XF8000790 0x00003FFF 0x00000305 - mask_write 0XF8000794 0x00003FFF 0x00000304 - mask_write 0XF8000798 0x00003FFF 0x00000304 - mask_write 0XF800079C 0x00003FFF 0x00000304 - mask_write 0XF80007A0 0x00003FFF 0x00000380 - mask_write 0XF80007A4 0x00003FFF 0x00000380 - mask_write 0XF80007A8 0x00003FFF 0x00000380 - mask_write 0XF80007AC 0x00003FFF 0x00000380 - mask_write 0XF80007B0 0x00003FFF 0x00000380 - mask_write 0XF80007B4 0x00003FFF 0x00000380 - mask_write 0XF80007B8 0x00003F01 0x00000200 - mask_write 0XF80007BC 0x00003F01 0x00000201 - mask_write 0XF80007C0 0x00003FFF 0x000002E0 - mask_write 0XF80007C4 0x00003FFF 0x000002E1 - mask_write 0XF80007C8 0x00003FFF 0x00000201 - mask_write 0XF80007CC 0x00003FFF 0x00000201 - mask_write 0XF80007D0 0x00003FFF 0x00000280 - mask_write 0XF80007D4 0x00003FFF 0x00000280 - mask_write 0XF8000830 0x003F0000 0x002F0000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_peripherals_init_data_1_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000B48 0x00000180 0x00000180 - mask_write 0XF8000B4C 0x00000180 0x00000180 - mask_write 0XF8000B50 0x00000180 0x00000180 - mask_write 0XF8000B54 0x00000180 0x00000180 - mask_write 0XF8000004 0x0000FFFF 0x0000767B - mask_write 0XE0001034 0x000000FF 0x00000006 - mask_write 0XE0001018 0x0000FFFF 0x0000003E - mask_write 0XE0001000 0x000001FF 0x00000017 - mask_write 0XE0001004 0x00000FFF 0x00000020 - mask_write 0XE0000034 0x000000FF 0x00000006 - mask_write 0XE0000018 0x0000FFFF 0x0000003E - mask_write 0XE0000000 0x000001FF 0x00000017 - mask_write 0XE0000004 0x00000FFF 0x00000020 - mask_write 0XF8007000 0x20000000 0x00000000 - mask_write 0XE000A244 0x003FFFFF 0x00004000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF4000 - mask_write 0XE000A248 0x003FFFFF 0x00004000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF0000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF4000 -} -proc ps7_post_config_1_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000900 0x0000000F 0x0000000F - mask_write 0XF8000240 0xFFFFFFFF 0xFFFFFFFF - mask_write 0XF8000240 0xFFFFFFFF 0x00000000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_pll_init_data_2_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000110 0x003FFFF0 0x001772C0 - mask_write 0XF8000100 0x0007F000 0x0001A000 - mask_write 0XF8000100 0x00000010 0x00000010 - mask_write 0XF8000100 0x00000001 0x00000001 - mask_write 0XF8000100 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000001 - mask_write 0XF8000100 0x00000010 0x00000000 - mask_write 0XF8000120 0x1F003F30 0x1F000200 - mask_write 0XF8000114 0x003FFFF0 0x001DB2C0 - mask_write 0XF8000104 0x0007F000 0x00015000 - mask_write 0XF8000104 0x00000010 0x00000010 - mask_write 0XF8000104 0x00000001 0x00000001 - mask_write 0XF8000104 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000002 - mask_write 0XF8000104 0x00000010 0x00000000 - mask_write 0XF8000124 0xFFF00003 0x0C200003 - mask_write 0XF8000118 0x003FFFF0 0x001F42C0 - mask_write 0XF8000108 0x0007F000 0x00014000 - mask_write 0XF8000108 0x00000010 0x00000010 - mask_write 0XF8000108 0x00000001 0x00000001 - mask_write 0XF8000108 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000004 - mask_write 0XF8000108 0x00000010 0x00000000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_clock_init_data_2_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000128 0x03F03F01 0x00203401 - mask_write 0XF8000138 0x00000011 0x00000001 - mask_write 0XF8000140 0x03F03F71 0x00100801 - mask_write 0XF800014C 0x00003F31 0x00000501 - mask_write 0XF8000150 0x00003F33 0x00001401 - mask_write 0XF8000154 0x00003F33 0x00001403 - mask_write 0XF8000168 0x00003F31 0x00000501 - mask_write 0XF8000170 0x03F03F30 0x00100A00 - mask_write 0XF8000180 0x03F03F30 0x00100630 - mask_write 0XF8000190 0x03F03F30 0x00203520 - mask_write 0XF80001A0 0x03F03F30 0x00100A00 - mask_write 0XF80001C4 0x00000001 0x00000001 - mask_write 0XF800012C 0x01FFCCCD 0x01FC044D - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_ddr_init_data_2_0 {} { - mask_write 0XF8006000 0x0001FFFF 0x00000080 - mask_write 0XF8006004 0x1FFFFFFF 0x0008107F - mask_write 0XF8006008 0x03FFFFFF 0x03C0780F - mask_write 0XF800600C 0x03FFFFFF 0x02001001 - mask_write 0XF8006010 0x03FFFFFF 0x00014001 - mask_write 0XF8006014 0x001FFFFF 0x0004151A - mask_write 0XF8006018 0xF7FFFFFF 0x44E354D2 - mask_write 0XF800601C 0xFFFFFFFF 0x720238E5 - mask_write 0XF8006020 0xFFFFFFFC 0x272872D0 - mask_write 0XF8006024 0x0FFFFFFF 0x0000003C - mask_write 0XF8006028 0x00003FFF 0x00002007 - mask_write 0XF800602C 0xFFFFFFFF 0x00000008 - mask_write 0XF8006030 0xFFFFFFFF 0x00040930 - mask_write 0XF8006034 0x13FF3FFF 0x00011014 - mask_write 0XF8006038 0x00001FC3 0x00000000 - mask_write 0XF800603C 0x000FFFFF 0x00000777 - mask_write 0XF8006040 0xFFFFFFFF 0xFFF00000 - mask_write 0XF8006044 0x0FFFFFFF 0x0FF66666 - mask_write 0XF8006048 0x3FFFFFFF 0x0003C248 - mask_write 0XF8006050 0xFF0F8FFF 0x77010800 - mask_write 0XF8006058 0x0001FFFF 0x00000101 - mask_write 0XF800605C 0x0000FFFF 0x00005003 - mask_write 0XF8006060 0x000017FF 0x0000003E - mask_write 0XF8006064 0x00021FE0 0x00020000 - mask_write 0XF8006068 0x03FFFFFF 0x00284141 - mask_write 0XF800606C 0x0000FFFF 0x00001610 - mask_write 0XF8006078 0x03FFFFFF 0x00466111 - mask_write 0XF800607C 0x000FFFFF 0x00032222 - mask_write 0XF80060A0 0x00FFFFFF 0x00008000 - mask_write 0XF80060A4 0xFFFFFFFF 0x10200802 - mask_write 0XF80060A8 0x0FFFFFFF 0x0670C845 - mask_write 0XF80060AC 0x000001FF 0x000001FE - mask_write 0XF80060B0 0x1FFFFFFF 0x1CFFFFFF - mask_write 0XF80060B4 0x000007FF 0x00000200 - mask_write 0XF80060B8 0x01FFFFFF 0x00200066 - mask_write 0XF80060C4 0x00000003 0x00000003 - mask_write 0XF80060C4 0x00000003 0x00000000 - mask_write 0XF80060C8 0x000000FF 0x00000000 - mask_write 0XF80060DC 0x00000001 0x00000000 - mask_write 0XF80060F0 0x0000FFFF 0x00000000 - mask_write 0XF80060F4 0x0000000F 0x00000008 - mask_write 0XF8006114 0x000000FF 0x00000000 - mask_write 0XF8006118 0x7FFFFFFF 0x40000001 - mask_write 0XF800611C 0x7FFFFFFF 0x40000001 - mask_write 0XF8006120 0x7FFFFFFF 0x40000001 - mask_write 0XF8006124 0x7FFFFFFF 0x40000001 - mask_write 0XF800612C 0x000FFFFF 0x00023C00 - mask_write 0XF8006130 0x000FFFFF 0x00022800 - mask_write 0XF8006134 0x000FFFFF 0x00022C00 - mask_write 0XF8006138 0x000FFFFF 0x00024800 - mask_write 0XF8006140 0x000FFFFF 0x00000035 - mask_write 0XF8006144 0x000FFFFF 0x00000035 - mask_write 0XF8006148 0x000FFFFF 0x00000035 - mask_write 0XF800614C 0x000FFFFF 0x00000035 - mask_write 0XF8006154 0x000FFFFF 0x00000077 - mask_write 0XF8006158 0x000FFFFF 0x0000007C - mask_write 0XF800615C 0x000FFFFF 0x0000007C - mask_write 0XF8006160 0x000FFFFF 0x00000075 - mask_write 0XF8006168 0x001FFFFF 0x000000E4 - mask_write 0XF800616C 0x001FFFFF 0x000000DF - mask_write 0XF8006170 0x001FFFFF 0x000000E0 - mask_write 0XF8006174 0x001FFFFF 0x000000E7 - mask_write 0XF800617C 0x000FFFFF 0x000000B7 - mask_write 0XF8006180 0x000FFFFF 0x000000BC - mask_write 0XF8006184 0x000FFFFF 0x000000BC - mask_write 0XF8006188 0x000FFFFF 0x000000B5 - mask_write 0XF8006190 0xFFFFFFFF 0x10040080 - mask_write 0XF8006194 0x000FFFFF 0x0001FC82 - mask_write 0XF8006204 0xFFFFFFFF 0x00000000 - mask_write 0XF8006208 0x000F03FF 0x000803FF - mask_write 0XF800620C 0x000F03FF 0x000803FF - mask_write 0XF8006210 0x000F03FF 0x000803FF - mask_write 0XF8006214 0x000F03FF 0x000803FF - mask_write 0XF8006218 0x000F03FF 0x000003FF - mask_write 0XF800621C 0x000F03FF 0x000003FF - mask_write 0XF8006220 0x000F03FF 0x000003FF - mask_write 0XF8006224 0x000F03FF 0x000003FF - mask_write 0XF80062A8 0x00000FF7 0x00000000 - mask_write 0XF80062AC 0xFFFFFFFF 0x00000000 - mask_write 0XF80062B0 0x003FFFFF 0x00005125 - mask_write 0XF80062B4 0x0003FFFF 0x000012A6 - mask_poll 0XF8000B74 0x00002000 - mask_write 0XF8006000 0x0001FFFF 0x00000081 - mask_poll 0XF8006054 0x00000007 -} -proc ps7_mio_init_data_2_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000B00 0x00000303 0x00000001 - mask_write 0XF8000B40 0x00000FFF 0x00000600 - mask_write 0XF8000B44 0x00000FFF 0x00000600 - mask_write 0XF8000B48 0x00000FFF 0x00000672 - mask_write 0XF8000B4C 0x00000FFF 0x00000672 - mask_write 0XF8000B50 0x00000FFF 0x00000674 - mask_write 0XF8000B54 0x00000FFF 0x00000674 - mask_write 0XF8000B58 0x00000FFF 0x00000600 - mask_write 0XF8000B5C 0xFFFFFFFF 0x00D6861C - mask_write 0XF8000B60 0xFFFFFFFF 0x00F9861C - mask_write 0XF8000B64 0xFFFFFFFF 0x00F9861C - mask_write 0XF8000B68 0xFFFFFFFF 0x00D6861C - mask_write 0XF8000B6C 0x00007FFF 0x00000E60 - mask_write 0XF8000B70 0x00000021 0x00000021 - mask_write 0XF8000B70 0x00000021 0x00000020 - mask_write 0XF8000B70 0x07FFFFFF 0x00000823 - mask_write 0XF8000700 0x00003FFF 0x00000600 - mask_write 0XF8000704 0x00003FFF 0x00000702 - mask_write 0XF8000708 0x00003FFF 0x00000702 - mask_write 0XF800070C 0x00003FFF 0x00000702 - mask_write 0XF8000710 0x00003FFF 0x00000702 - mask_write 0XF8000714 0x00003FFF 0x00000702 - mask_write 0XF8000718 0x00003FFF 0x00000702 - mask_write 0XF800071C 0x00003FFF 0x00000600 - mask_write 0XF8000720 0x00003FFF 0x00000702 - mask_write 0XF8000724 0x00003FFF 0x00000600 - mask_write 0XF8000728 0x00003FFF 0x00001640 - mask_write 0XF800072C 0x00003FFF 0x00001640 - mask_write 0XF8000730 0x00003FFF 0x00000640 - mask_write 0XF8000734 0x00003FFF 0x00000640 - mask_write 0XF8000738 0x00003FFF 0x00000600 - mask_write 0XF800073C 0x00003FFF 0x00000600 - mask_write 0XF8000740 0x00003FFF 0x00002902 - mask_write 0XF8000744 0x00003FFF 0x00002902 - mask_write 0XF8000748 0x00003FFF 0x00002902 - mask_write 0XF800074C 0x00003FFF 0x00002902 - mask_write 0XF8000750 0x00003FFF 0x00002902 - mask_write 0XF8000754 0x00003FFF 0x00002902 - mask_write 0XF8000758 0x00003FFF 0x00000903 - mask_write 0XF800075C 0x00003FFF 0x00000903 - mask_write 0XF8000760 0x00003FFF 0x00000903 - mask_write 0XF8000764 0x00003FFF 0x00000903 - mask_write 0XF8000768 0x00003FFF 0x00000903 - mask_write 0XF800076C 0x00003FFF 0x00000903 - mask_write 0XF8000770 0x00003FFF 0x00000304 - mask_write 0XF8000774 0x00003FFF 0x00000305 - mask_write 0XF8000778 0x00003FFF 0x00000304 - mask_write 0XF800077C 0x00003FFF 0x00000305 - mask_write 0XF8000780 0x00003FFF 0x00000304 - mask_write 0XF8000784 0x00003FFF 0x00000304 - mask_write 0XF8000788 0x00003FFF 0x00000304 - mask_write 0XF800078C 0x00003FFF 0x00000304 - mask_write 0XF8000790 0x00003FFF 0x00000305 - mask_write 0XF8000794 0x00003FFF 0x00000304 - mask_write 0XF8000798 0x00003FFF 0x00000304 - mask_write 0XF800079C 0x00003FFF 0x00000304 - mask_write 0XF80007A0 0x00003FFF 0x00000380 - mask_write 0XF80007A4 0x00003FFF 0x00000380 - mask_write 0XF80007A8 0x00003FFF 0x00000380 - mask_write 0XF80007AC 0x00003FFF 0x00000380 - mask_write 0XF80007B0 0x00003FFF 0x00000380 - mask_write 0XF80007B4 0x00003FFF 0x00000380 - mask_write 0XF80007B8 0x00003F01 0x00000200 - mask_write 0XF80007BC 0x00003F01 0x00000201 - mask_write 0XF80007C0 0x00003FFF 0x000002E0 - mask_write 0XF80007C4 0x00003FFF 0x000002E1 - mask_write 0XF80007C8 0x00003FFF 0x00000201 - mask_write 0XF80007CC 0x00003FFF 0x00000201 - mask_write 0XF80007D0 0x00003FFF 0x00000280 - mask_write 0XF80007D4 0x00003FFF 0x00000280 - mask_write 0XF8000830 0x003F0000 0x002F0000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_peripherals_init_data_2_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000B48 0x00000180 0x00000180 - mask_write 0XF8000B4C 0x00000180 0x00000180 - mask_write 0XF8000B50 0x00000180 0x00000180 - mask_write 0XF8000B54 0x00000180 0x00000180 - mask_write 0XF8000004 0x0000FFFF 0x0000767B - mask_write 0XE0001034 0x000000FF 0x00000006 - mask_write 0XE0001018 0x0000FFFF 0x0000003E - mask_write 0XE0001000 0x000001FF 0x00000017 - mask_write 0XE0001004 0x00000FFF 0x00000020 - mask_write 0XE0000034 0x000000FF 0x00000006 - mask_write 0XE0000018 0x0000FFFF 0x0000003E - mask_write 0XE0000000 0x000001FF 0x00000017 - mask_write 0XE0000004 0x00000FFF 0x00000020 - mask_write 0XE000D000 0x00080000 0x00080000 - mask_write 0XF8007000 0x20000000 0x00000000 - mask_write 0XE000A244 0x003FFFFF 0x00004000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF4000 - mask_write 0XE000A248 0x003FFFFF 0x00004000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF0000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF4000 -} -proc ps7_post_config_2_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000900 0x0000000F 0x0000000F - mask_write 0XF8000240 0xFFFFFFFF 0xFFFFFFFF - mask_write 0XF8000240 0xFFFFFFFF 0x00000000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_pll_init_data_3_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000110 0x003FFFF0 0x001772C0 - mask_write 0XF8000100 0x0007F000 0x0001A000 - mask_write 0XF8000100 0x00000010 0x00000010 - mask_write 0XF8000100 0x00000001 0x00000001 - mask_write 0XF8000100 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000001 - mask_write 0XF8000100 0x00000010 0x00000000 - mask_write 0XF8000120 0x1F003F30 0x1F000200 - mask_write 0XF8000114 0x003FFFF0 0x001DB2C0 - mask_write 0XF8000104 0x0007F000 0x00015000 - mask_write 0XF8000104 0x00000010 0x00000010 - mask_write 0XF8000104 0x00000001 0x00000001 - mask_write 0XF8000104 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000002 - mask_write 0XF8000104 0x00000010 0x00000000 - mask_write 0XF8000124 0xFFF00003 0x0C200003 - mask_write 0XF8000118 0x003FFFF0 0x001F42C0 - mask_write 0XF8000108 0x0007F000 0x00014000 - mask_write 0XF8000108 0x00000010 0x00000010 - mask_write 0XF8000108 0x00000001 0x00000001 - mask_write 0XF8000108 0x00000001 0x00000000 - mask_poll 0XF800010C 0x00000004 - mask_write 0XF8000108 0x00000010 0x00000000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_clock_init_data_3_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000128 0x03F03F01 0x00203401 - mask_write 0XF8000138 0x00000011 0x00000001 - mask_write 0XF8000140 0x03F03F71 0x00100801 - mask_write 0XF800014C 0x00003F31 0x00000501 - mask_write 0XF8000150 0x00003F33 0x00001401 - mask_write 0XF8000154 0x00003F33 0x00001403 - mask_write 0XF8000168 0x00003F31 0x00000501 - mask_write 0XF8000170 0x03F03F30 0x00100A00 - mask_write 0XF8000180 0x03F03F30 0x00100630 - mask_write 0XF8000190 0x03F03F30 0x00203520 - mask_write 0XF80001A0 0x03F03F30 0x00100A00 - mask_write 0XF80001C4 0x00000001 0x00000001 - mask_write 0XF800012C 0x01FFCCCD 0x01FC044D - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_ddr_init_data_3_0 {} { - mask_write 0XF8006000 0x0001FFFF 0x00000080 - mask_write 0XF8006004 0x0007FFFF 0x0000107F - mask_write 0XF8006008 0x03FFFFFF 0x03C0780F - mask_write 0XF800600C 0x03FFFFFF 0x02001001 - mask_write 0XF8006010 0x03FFFFFF 0x00014001 - mask_write 0XF8006014 0x001FFFFF 0x0004151A - mask_write 0XF8006018 0xF7FFFFFF 0x44E354D2 - mask_write 0XF800601C 0xFFFFFFFF 0x720238E5 - mask_write 0XF8006020 0x7FDFFFFC 0x270872D0 - mask_write 0XF8006024 0x0FFFFFC3 0x00000000 - mask_write 0XF8006028 0x00003FFF 0x00002007 - mask_write 0XF800602C 0xFFFFFFFF 0x00000008 - mask_write 0XF8006030 0xFFFFFFFF 0x00040930 - mask_write 0XF8006034 0x13FF3FFF 0x00011014 - mask_write 0XF8006038 0x00000003 0x00000000 - mask_write 0XF800603C 0x000FFFFF 0x00000777 - mask_write 0XF8006040 0xFFFFFFFF 0xFFF00000 - mask_write 0XF8006044 0x0FFFFFFF 0x0FF66666 - mask_write 0XF8006048 0x0003F000 0x0003C000 - mask_write 0XF8006050 0xFF0F8FFF 0x77010800 - mask_write 0XF8006058 0x00010000 0x00000000 - mask_write 0XF800605C 0x0000FFFF 0x00005003 - mask_write 0XF8006060 0x000017FF 0x0000003E - mask_write 0XF8006064 0x00021FE0 0x00020000 - mask_write 0XF8006068 0x03FFFFFF 0x00284141 - mask_write 0XF800606C 0x0000FFFF 0x00001610 - mask_write 0XF8006078 0x03FFFFFF 0x00466111 - mask_write 0XF800607C 0x000FFFFF 0x00032222 - mask_write 0XF80060A4 0xFFFFFFFF 0x10200802 - mask_write 0XF80060A8 0x0FFFFFFF 0x0670C845 - mask_write 0XF80060AC 0x000001FF 0x000001FE - mask_write 0XF80060B0 0x1FFFFFFF 0x1CFFFFFF - mask_write 0XF80060B4 0x00000200 0x00000200 - mask_write 0XF80060B8 0x01FFFFFF 0x00200066 - mask_write 0XF80060C4 0x00000003 0x00000003 - mask_write 0XF80060C4 0x00000003 0x00000000 - mask_write 0XF80060C8 0x000000FF 0x00000000 - mask_write 0XF80060DC 0x00000001 0x00000000 - mask_write 0XF80060F0 0x0000FFFF 0x00000000 - mask_write 0XF80060F4 0x0000000F 0x00000008 - mask_write 0XF8006114 0x000000FF 0x00000000 - mask_write 0XF8006118 0x7FFFFFCF 0x40000001 - mask_write 0XF800611C 0x7FFFFFCF 0x40000001 - mask_write 0XF8006120 0x7FFFFFCF 0x40000001 - mask_write 0XF8006124 0x7FFFFFCF 0x40000001 - mask_write 0XF800612C 0x000FFFFF 0x00023C00 - mask_write 0XF8006130 0x000FFFFF 0x00022800 - mask_write 0XF8006134 0x000FFFFF 0x00022C00 - mask_write 0XF8006138 0x000FFFFF 0x00024800 - mask_write 0XF8006140 0x000FFFFF 0x00000035 - mask_write 0XF8006144 0x000FFFFF 0x00000035 - mask_write 0XF8006148 0x000FFFFF 0x00000035 - mask_write 0XF800614C 0x000FFFFF 0x00000035 - mask_write 0XF8006154 0x000FFFFF 0x00000077 - mask_write 0XF8006158 0x000FFFFF 0x0000007C - mask_write 0XF800615C 0x000FFFFF 0x0000007C - mask_write 0XF8006160 0x000FFFFF 0x00000075 - mask_write 0XF8006168 0x001FFFFF 0x000000E4 - mask_write 0XF800616C 0x001FFFFF 0x000000DF - mask_write 0XF8006170 0x001FFFFF 0x000000E0 - mask_write 0XF8006174 0x001FFFFF 0x000000E7 - mask_write 0XF800617C 0x000FFFFF 0x000000B7 - mask_write 0XF8006180 0x000FFFFF 0x000000BC - mask_write 0XF8006184 0x000FFFFF 0x000000BC - mask_write 0XF8006188 0x000FFFFF 0x000000B5 - mask_write 0XF8006190 0x6FFFFEFE 0x00040080 - mask_write 0XF8006194 0x000FFFFF 0x0001FC82 - mask_write 0XF8006204 0xFFFFFFFF 0x00000000 - mask_write 0XF8006208 0x000703FF 0x000003FF - mask_write 0XF800620C 0x000703FF 0x000003FF - mask_write 0XF8006210 0x000703FF 0x000003FF - mask_write 0XF8006214 0x000703FF 0x000003FF - mask_write 0XF8006218 0x000F03FF 0x000003FF - mask_write 0XF800621C 0x000F03FF 0x000003FF - mask_write 0XF8006220 0x000F03FF 0x000003FF - mask_write 0XF8006224 0x000F03FF 0x000003FF - mask_write 0XF80062A8 0x00000FF5 0x00000000 - mask_write 0XF80062AC 0xFFFFFFFF 0x00000000 - mask_write 0XF80062B0 0x003FFFFF 0x00005125 - mask_write 0XF80062B4 0x0003FFFF 0x000012A6 - mask_poll 0XF8000B74 0x00002000 - mask_write 0XF8006000 0x0001FFFF 0x00000081 - mask_poll 0XF8006054 0x00000007 -} -proc ps7_mio_init_data_3_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000B00 0x00000071 0x00000001 - mask_write 0XF8000B40 0x00000FFE 0x00000600 - mask_write 0XF8000B44 0x00000FFE 0x00000600 - mask_write 0XF8000B48 0x00000FFE 0x00000672 - mask_write 0XF8000B4C 0x00000FFE 0x00000672 - mask_write 0XF8000B50 0x00000FFE 0x00000674 - mask_write 0XF8000B54 0x00000FFE 0x00000674 - mask_write 0XF8000B58 0x00000FFE 0x00000600 - mask_write 0XF8000B6C 0x0000027F 0x00000260 - mask_write 0XF8000B70 0x00000001 0x00000001 - mask_write 0XF8000B70 0x00000001 0x00000000 - mask_write 0XF8000B70 0x001E3FC3 0x00000803 - mask_write 0XF8000700 0x00003FFF 0x00000600 - mask_write 0XF8000704 0x00003FFF 0x00000702 - mask_write 0XF8000708 0x00003FFF 0x00000702 - mask_write 0XF800070C 0x00003FFF 0x00000702 - mask_write 0XF8000710 0x00003FFF 0x00000702 - mask_write 0XF8000714 0x00003FFF 0x00000702 - mask_write 0XF8000718 0x00003FFF 0x00000702 - mask_write 0XF800071C 0x00003FFF 0x00000600 - mask_write 0XF8000720 0x00003FFF 0x00000702 - mask_write 0XF8000724 0x00003FFF 0x00000600 - mask_write 0XF8000728 0x00003FFF 0x00001640 - mask_write 0XF800072C 0x00003FFF 0x00001640 - mask_write 0XF8000730 0x00003FFF 0x00000640 - mask_write 0XF8000734 0x00003FFF 0x00000640 - mask_write 0XF8000738 0x00003FFF 0x00000600 - mask_write 0XF800073C 0x00003FFF 0x00000600 - mask_write 0XF8000740 0x00003FFF 0x00002902 - mask_write 0XF8000744 0x00003FFF 0x00002902 - mask_write 0XF8000748 0x00003FFF 0x00002902 - mask_write 0XF800074C 0x00003FFF 0x00002902 - mask_write 0XF8000750 0x00003FFF 0x00002902 - mask_write 0XF8000754 0x00003FFF 0x00002902 - mask_write 0XF8000758 0x00003FFF 0x00000903 - mask_write 0XF800075C 0x00003FFF 0x00000903 - mask_write 0XF8000760 0x00003FFF 0x00000903 - mask_write 0XF8000764 0x00003FFF 0x00000903 - mask_write 0XF8000768 0x00003FFF 0x00000903 - mask_write 0XF800076C 0x00003FFF 0x00000903 - mask_write 0XF8000770 0x00003FFF 0x00000304 - mask_write 0XF8000774 0x00003FFF 0x00000305 - mask_write 0XF8000778 0x00003FFF 0x00000304 - mask_write 0XF800077C 0x00003FFF 0x00000305 - mask_write 0XF8000780 0x00003FFF 0x00000304 - mask_write 0XF8000784 0x00003FFF 0x00000304 - mask_write 0XF8000788 0x00003FFF 0x00000304 - mask_write 0XF800078C 0x00003FFF 0x00000304 - mask_write 0XF8000790 0x00003FFF 0x00000305 - mask_write 0XF8000794 0x00003FFF 0x00000304 - mask_write 0XF8000798 0x00003FFF 0x00000304 - mask_write 0XF800079C 0x00003FFF 0x00000304 - mask_write 0XF80007A0 0x00003FFF 0x00000380 - mask_write 0XF80007A4 0x00003FFF 0x00000380 - mask_write 0XF80007A8 0x00003FFF 0x00000380 - mask_write 0XF80007AC 0x00003FFF 0x00000380 - mask_write 0XF80007B0 0x00003FFF 0x00000380 - mask_write 0XF80007B4 0x00003FFF 0x00000380 - mask_write 0XF80007B8 0x00003F01 0x00000200 - mask_write 0XF80007BC 0x00003F01 0x00000201 - mask_write 0XF80007C0 0x00003FFF 0x000002E0 - mask_write 0XF80007C4 0x00003FFF 0x000002E1 - mask_write 0XF80007C8 0x00003FFF 0x00000201 - mask_write 0XF80007CC 0x00003FFF 0x00000201 - mask_write 0XF80007D0 0x00003FFF 0x00000280 - mask_write 0XF80007D4 0x00003FFF 0x00000280 - mask_write 0XF8000830 0x003F0000 0x002F0000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -proc ps7_peripherals_init_data_3_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000B48 0x00000180 0x00000180 - mask_write 0XF8000B4C 0x00000180 0x00000180 - mask_write 0XF8000B50 0x00000180 0x00000180 - mask_write 0XF8000B54 0x00000180 0x00000180 - mask_write 0XF8000004 0x0000FFFF 0x0000767B - mask_write 0XE0001034 0x000000FF 0x00000006 - mask_write 0XE0001018 0x0000FFFF 0x0000003E - mask_write 0XE0001000 0x000001FF 0x00000017 - mask_write 0XE0001004 0x000003FF 0x00000020 - mask_write 0XE0000034 0x000000FF 0x00000006 - mask_write 0XE0000018 0x0000FFFF 0x0000003E - mask_write 0XE0000000 0x000001FF 0x00000017 - mask_write 0XE0000004 0x000003FF 0x00000020 - mask_write 0XE000D000 0x00080000 0x00080000 - mask_write 0XF8007000 0x20000000 0x00000000 - mask_write 0XE000A244 0x003FFFFF 0x00004000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF4000 - mask_write 0XE000A248 0x003FFFFF 0x00004000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF0000 - mask_write 0XE000A008 0xFFFFFFFF 0xBFFF4000 -} -proc ps7_post_config_3_0 {} { - mask_write 0XF8000008 0x0000FFFF 0x0000DF0D - mask_write 0XF8000900 0x0000000F 0x0000000F - mask_write 0XF8000240 0xFFFFFFFF 0xFFFFFFFF - mask_write 0XF8000240 0xFFFFFFFF 0x00000000 - mask_write 0XF8000004 0x0000FFFF 0x0000767B -} -set PCW_SILICON_VER_1_0 "0x0" -set PCW_SILICON_VER_2_0 "0x1" -set PCW_SILICON_VER_3_0 "0x2" - - - -proc mask_poll { addr mask } { - set curval "0x[string range [mrd $addr] end-8 end]" - set maskedval [expr {$curval & $mask}] - while { $maskedval == 0 } { - set curval "0x[string range [mrd $addr] end-8 end]" - set maskedval [expr {$curval & $mask}] - } -} - -proc ps_version { } { - set si_ver "0x[string range [mrd 0xF8007080] end-8 end]" - set mask_sil_ver "0x[expr {$si_ver >> 28}]" - return $mask_sil_ver; -} - -proc ps7_post_config {} { - variable PCW_SILICON_VER_1_0 - variable PCW_SILICON_VER_2_0 - variable PCW_SILICON_VER_3_0 - set sil_ver [ps_version] - - if { $sil_ver == $PCW_SILICON_VER_1_0} { - ps7_post_config_1_0 - } elseif { $sil_ver == $PCW_SILICON_VER_2_0 } { - ps7_post_config_2_0 - } else { - ps7_post_config_3_0 - } -} - -proc ps7_init {} { - variable PCW_SILICON_VER_1_0 - variable PCW_SILICON_VER_2_0 - variable PCW_SILICON_VER_3_0 - set sil_ver [ps_version] - - if { $sil_ver == $PCW_SILICON_VER_1_0} { - ps7_mio_init_data_1_0 - ps7_pll_init_data_1_0 - ps7_clock_init_data_1_0 - ps7_ddr_init_data_1_0 - ps7_peripherals_init_data_1_0 - #puts "PCW Silicon Version : 1.0" - } elseif { $sil_ver == $PCW_SILICON_VER_2_0 } { - ps7_mio_init_data_2_0 - ps7_pll_init_data_2_0 - ps7_clock_init_data_2_0 - ps7_ddr_init_data_2_0 - ps7_peripherals_init_data_2_0 - #puts "PCW Silicon Version : 2.0" - } else { - ps7_mio_init_data_3_0 - ps7_pll_init_data_3_0 - ps7_clock_init_data_3_0 - ps7_ddr_init_data_3_0 - ps7_peripherals_init_data_3_0 - #puts "PCW Silicon Version : 3.0" - } -} diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/.cproject b/quad/xsdk_workspace/zybo_fsbl_bsp/.cproject index d01a3047c9fa0ed118a5358404b92ab2b2c2fc31..5129f789af122de2e3a649f495991df8ea4f0b4e 100644 --- a/quad/xsdk_workspace/zybo_fsbl_bsp/.cproject +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/.cproject @@ -3,8 +3,8 @@ <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"> + <cconfiguration id="org.eclipse.cdt.core.default.config.1389527391"> + <storageModule buildSystemId="org.eclipse.cdt.core.defaultConfigDataProvider" id="org.eclipse.cdt.core.default.config.1389527391" moduleId="org.eclipse.cdt.core.settings" name="Configuration"> <externalSettings/> <extensions/> </storageModule> diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/.project b/quad/xsdk_workspace/zybo_fsbl_bsp/.project index db7920e2db6569999084baf805b3d45df40aab13..9b0b646a377bd2ee0bc4cb7321145a43ce57bf2a 100644 --- a/quad/xsdk_workspace/zybo_fsbl_bsp/.project +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/.project @@ -3,7 +3,7 @@ <name>zybo_fsbl_bsp</name> <comment></comment> <projects> - <project>system_hw_platform</project> + <project>sytem_hw_platform</project> </projects> <buildSpec> <buildCommand> diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/libgen.options b/quad/xsdk_workspace/zybo_fsbl_bsp/libgen.options index ac5ba396687b73316827155661d71b9247b953be..c7623d91f4a1e0004da3838082aea20358655cc9 100644 --- a/quad/xsdk_workspace/zybo_fsbl_bsp/libgen.options +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/libgen.options @@ -1,3 +1,3 @@ PROCESSOR=ps7_cortexa9_0 REPOSITORIES= -HWSPEC=../system_hw_platform/system.xml +HWSPEC=../sytem_hw_platform/system.xml diff --git a/quad/xsdk_workspace/zybo_fsbl_bsp/system.mss b/quad/xsdk_workspace/zybo_fsbl_bsp/system.mss index f6a16bfdc89cf14e12ce15914d7218be2055b907..901e54a471058d3b3cfbef52689f574ae2ceb2d3 100644 --- a/quad/xsdk_workspace/zybo_fsbl_bsp/system.mss +++ b/quad/xsdk_workspace/zybo_fsbl_bsp/system.mss @@ -120,6 +120,12 @@ BEGIN DRIVER PARAMETER HW_INSTANCE = ps7_i2c_0 END +BEGIN DRIVER + PARAMETER DRIVER_NAME = iicps + PARAMETER DRIVER_VER = 1.04.a + PARAMETER HW_INSTANCE = ps7_i2c_1 +END + BEGIN DRIVER PARAMETER DRIVER_NAME = generic PARAMETER DRIVER_VER = 1.00.a diff --git a/website/content/computation_graph.md b/website/content/computation_graph.md new file mode 100644 index 0000000000000000000000000000000000000000..0f955b19ceea85b6bb1455477a75aee37b5b00a4 --- /dev/null +++ b/website/content/computation_graph.md @@ -0,0 +1,15 @@ +Title: A new and flexible way to compute +Date: 2017-02-01 +Authors: Brendan +Category: Highlights +thumbnail: "/images/computation_graph.png" + +The controls team wants to start tuning the controller on the quadcopter, they also want to have the modify the controller in order to better characterize each part. Currently, there is no way to do that except re-write the code on the quad, which bleeds into their development cycle. David took the challenge to solve this issue, and developed the idea of a computation graph. + +<a href="/images/computation_graph.png"> +<figure> +<img src="/images/computation_graph.png"> +</figure> +</a> + +The idea is a typical graph data structure, specifically a directed acyclic multigraph with weighted edges. However, when normally the nodes in a graph represent some data, the nodes in the computation represent functions, and each edge represents a value that gets passed from the "output" of one node to the "input" of another node. Computing the whole graph is simply a matter of performing a depth-first-search algorithm, where the "inputs" of a node represent the node's children. \ No newline at end of file diff --git a/website/content/finding_discrepencies.md b/website/content/finding_discrepencies.md new file mode 100644 index 0000000000000000000000000000000000000000..1e93eed9341080194281c38f97ee1075767f28ac --- /dev/null +++ b/website/content/finding_discrepencies.md @@ -0,0 +1,21 @@ +Title: Tracking Down Discrepancies +Date: 2017-03-28 +Authors: Brendan +Category: Highlights +thumbnail: "/images/discrepancies_bad.png" + +David, Andy, and Tara have been trying to track down discrepancies between the quadcopter controller implementation and the Simulink model. With each discovered discrepancy, the model keeps getting better. Here is one example of where the quad code and model were performing the calculation for the complementary filter differently. + +<a href="/images/discrepancies_bad.png"> +<figure> +<img src="/images/discrepancies_bad.png"> +</figure> +</a> + +This is looking at the output of a simulation in the Simulink model, overlayed with actual logged data from a flight test of the quadcopter. After resolving the discrepency, the model predicts the behavior much more closely. + +<a href="/images/discrepancies_good.png"> +<figure> +<img src="/images/discrepancies_good.png"> +</figure> +</a> \ No newline at end of file diff --git a/website/content/height_stabilization.md b/website/content/height_stabilization.md deleted file mode 100644 index dc28ec032ab293bcd7577f5bd2f72b27f1d88da3..0000000000000000000000000000000000000000 --- a/website/content/height_stabilization.md +++ /dev/null @@ -1,13 +0,0 @@ -Title: Height Stabilization (movie) -Date: 2016-12-04 -Authors: Brendan -Category: Highlights -image: - -The following test flight demonstrates altitude stabilization. Once the pilot puts the quadcopter into autonomous mode, the quadcopter uses its internal control algorithm to maintain its altitude. The pilot still must provide x and y-axis stabilization through the remote control. - -<figure> -<video controls> -<source src="/videos/height_stabilization.mp4"> -</video> -</figure> diff --git a/website/content/images/computation_graph.png b/website/content/images/computation_graph.png new file mode 100644 index 0000000000000000000000000000000000000000..79f6ad79766f226b7101cd6e9e5d0bb62d7ee071 Binary files /dev/null and b/website/content/images/computation_graph.png differ diff --git a/website/content/images/discrepancies_bad.png b/website/content/images/discrepancies_bad.png new file mode 100644 index 0000000000000000000000000000000000000000..b549628ecbaa5e329a677365cc632027a95c274a Binary files /dev/null and b/website/content/images/discrepancies_bad.png differ diff --git a/website/content/images/discrepancies_good.png b/website/content/images/discrepancies_good.png new file mode 100644 index 0000000000000000000000000000000000000000..4506945f7c5dde49542e1349d675f0db28538389 Binary files /dev/null and b/website/content/images/discrepancies_good.png differ diff --git a/website/content/images/model_pitch_rate.png b/website/content/images/model_pitch_rate.png new file mode 100644 index 0000000000000000000000000000000000000000..623f0214a3e4402a6e0b559b1881f9a5d4ae6c66 Binary files /dev/null and b/website/content/images/model_pitch_rate.png differ diff --git a/website/content/model_pitch_rate.md b/website/content/model_pitch_rate.md new file mode 100644 index 0000000000000000000000000000000000000000..5b8c8a5fa7562d3e68f2a97abfa57146d79f87f0 --- /dev/null +++ b/website/content/model_pitch_rate.md @@ -0,0 +1,15 @@ +Title: Simulink Model Update +Date: 2017-02-10 +Authors: Brendan +Category: Highlights +thumbnail: "/images/model_pitch_rate.png" + +Andy and Tara have been working to flesh out the Simulink model of our quadcopter. They have obtained the measurements they need to physically describe the model, now they are finishing up the Simulink model. Here is an example output of the pitch position controller. + +<a href="/images/model_pitch_rate.png"> +<figure> +<img src="/images/model_pitch_rate.png"> +</figure> +</a> + +This controller represents one of many controllers that we consider to be "inner loop" controllers. Right now, the inner loop controllers in the model are stable, like this pitch position controller. The controls team is now working through PID constants to determine a stable controller for the outer loop controllers. \ No newline at end of file diff --git a/website/content/pages/about.md b/website/content/pages/about.md index 3059f09b11e2b4a8d5a26f0e1d8a2995b33ca17e..156c09c8445c343db83cd355c1cdf2d996bd8775 100644 --- a/website/content/pages/about.md +++ b/website/content/pages/about.md @@ -17,8 +17,7 @@ embedded systems. This year, our team is responsible for advancing the modular structure the platform, developing a controls model, and improving the autonomous flight capabilities of the quadcopter. -For additional information regarding the project, please visit the -[supplemental wiki -page][1]. +Team members should consult the [Gitlab project page][1] for technical +documentation and instructions. -[1]: https://wikis.ece.iastate.edu/microcart-senior-design/index.php/2016-2017_Main_Page +[1]: https://git.ece.iastate.edu/danc/MicroCART_17-18 diff --git a/website/themes/notmyidea/templates/base.html b/website/themes/notmyidea/templates/base.html index 455bcb40aee9fc6ac6c167ff43d142bed100ac4f..c4739eed4c5781e4c474fba1537a4a3e3eae71d5 100644 --- a/website/themes/notmyidea/templates/base.html +++ b/website/themes/notmyidea/templates/base.html @@ -36,7 +36,6 @@ <li{% if cat == category %} class="active"{% endif %}><a href="{{ SITEURL }}/{{ cat.url }}">{{ cat }}</a></li> {% endfor %} {% endif %} - <li><a href="https://wikis.ece.iastate.edu/microcart-senior-design/index.php/2016-2017_Main_Page">Wiki</a></li> </ul></nav> </header><!-- /#banner --> {% block content %} diff --git a/wifi_bridge/test_scripts/tcp_timer.py b/wifi_bridge/test_scripts/tcp_timer.py index 78664a980b15574af94a883fd654dfd71d85696c..6732f05012b8b354e36188a2f5b54822cc2933b9 100644 --- a/wifi_bridge/test_scripts/tcp_timer.py +++ b/wifi_bridge/test_scripts/tcp_timer.py @@ -11,12 +11,12 @@ TCP_PORT = 8080 message = bytes(range(36)) times_full = [] times_network = [] -times = [0.0]*100 +times = [0.0]*200 dropped = True response = bytes("initial", 'ASCII') addr = "initial" recvd_data = [] -for i in range(100): +for i in range(200): if dropped: sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_NODELAY, 1) @@ -51,11 +51,10 @@ for i in range(100): while time.perf_counter() - send_time < 0.01: pass -# with open("tcp_dist.csv", 'w', newline='') as f: -# writer = csv.writer(f) -# for time in times_network: -# time = time + 2.6 -# writer.writerow([time]) + with open("tcp_dist.csv", 'w', newline='') as f: + writer = csv.writer(f) + for t in times_network: + writer.writerow([t]) for time in [times_full, times_network]: print("lowest: " + str(min(time)))